Skip to content
Snippets Groups Projects
Commit 7d1c4af2 authored by Joan Solà Ortega's avatar Joan Solà Ortega
Browse files

Fix old test for odomtery 3D

parent 73b42974
No related branches found
No related tags found
1 merge request!188Processors api
Pipeline #
...@@ -53,15 +53,19 @@ int main (int argc, char** argv) ...@@ -53,15 +53,19 @@ int main (int argc, char** argv)
CeresManager ceres_manager(problem, ceres_options); CeresManager ceres_manager(problem, ceres_options);
SensorBasePtr sen = problem->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml"); SensorBasePtr sen = problem->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
problem->installProcessor("ODOM 3D", "odometry integrator", "odom"); ProcessorParamsOdom3DPtr proc_params = std::make_shared<ProcessorParamsOdom3D>();
problem->getProcessorMotionPtr()->setOrigin((Vector7s()<<0,0,0,0,0,0,1).finished(), TimeStamp(0)); problem->installProcessor("ODOM 3D", "odometry integrator", sen, proc_params);
// Time and prior
Scalar dt = 0.1;
problem->setPrior((Vector7s()<<0,0,0,0,0,0,1).finished(), Matrix6s::Identity() * 1e-8, TimeStamp(0), dt/2);
// Motion data
Scalar dx = .1; Scalar dx = .1;
Scalar dyaw = 2*M_PI/5; Scalar dyaw = 2*M_PI/5;
Vector6s data((Vector6s() << dx*cos(dyaw/2),dx*sin(dyaw/2),0,0,0,dyaw).finished()); // will integrate this data repeatedly Vector6s data((Vector6s() << dx*cos(dyaw/2),dx*sin(dyaw/2),0,0,0,dyaw).finished()); // will integrate this data repeatedly
Scalar dt = 0.1;
CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(TimeStamp(0), sen, data, 7, 6, nullptr); CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(TimeStamp(0), sen, data, 7, 6, nullptr);
cout << "t: " << std::setprecision(2) << 0 << " \t x = ( " << problem->getCurrentState().transpose() << ")" << endl; cout << "t: " << std::setprecision(2) << 0 << " \t x = ( " << problem->getCurrentState().transpose() << ")" << endl;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment