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

Improve creator of prc diff drv

parent 303c7c68
No related branches found
No related tags found
2 merge requests!312Adress 244: Do not use default yaml params,!305WIP: Resolve "Do not use default YAML params"
Pipeline #4126 passed
...@@ -187,19 +187,9 @@ FactorBasePtr ProcessorDiffDrive::emplaceFactor(FeatureBasePtr _feature, ...@@ -187,19 +187,9 @@ FactorBasePtr ProcessorDiffDrive::emplaceFactor(FeatureBasePtr _feature,
ProcessorBasePtr ProcessorDiffDrive::createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr) ProcessorBasePtr ProcessorDiffDrive::createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr)
{ {
auto params = std::make_shared<ProcessorParamsDiffDrive>(_unique_name, _server);
ProcessorDiffDrivePtr prc_ptr; auto prc_ptr = std::make_shared<ProcessorDiffDrive>(params);
std::shared_ptr<ProcessorParamsDiffDrive> params;
params = std::make_shared<ProcessorParamsDiffDrive>();
params->voting_active = _server.getParam<bool>(_unique_name + "/voting_active");
params->time_tolerance = _server.getParam<double>(_unique_name + "/time_tolerance");
params->max_time_span = _server.getParam<double>(_unique_name + "/max_time_span");
params->dist_traveled = _server.getParam<double>(_unique_name + "/dist_traveled"); // Will make KFs automatically every 1m displacement
params->angle_turned = _server.getParam<double>(_unique_name + "/angle_turned");
params->unmeasured_perturbation_std = _server.getParam<double>(_unique_name + "/unmeasured_perturbation_std");
prc_ptr = std::make_shared<ProcessorDiffDrive>(params);
prc_ptr->setName(_unique_name); prc_ptr->setName(_unique_name);
return prc_ptr; return prc_ptr;
......
...@@ -186,12 +186,9 @@ ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const ...@@ -186,12 +186,9 @@ ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const
ProcessorBasePtr ProcessorOdom2D::createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr) ProcessorBasePtr ProcessorOdom2D::createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr)
{ {
ProcessorOdom2DPtr prc_ptr; auto params = std::make_shared<ProcessorParamsOdom2D>(_unique_name, _server);
std::shared_ptr<ProcessorParamsOdom2D> params;
params = std::make_shared<ProcessorParamsOdom2D>(_unique_name, _server);
prc_ptr = std::make_shared<ProcessorOdom2D>(params); auto prc_ptr = std::make_shared<ProcessorOdom2D>(params);
prc_ptr->setName(_unique_name); prc_ptr->setName(_unique_name);
return prc_ptr; return prc_ptr;
......
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