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

Completely remove sensor from create() and createAutoConf()

parent 3f2dafe6
No related branches found
No related tags found
1 merge request!313WIP: Resolve "Processor constructors and creators requiring a sensor pointer?"
Pipeline #4159 passed
Showing
with 36 additions and 47 deletions
......@@ -100,8 +100,7 @@ void ProcessorRangeBearing::processCapture(CaptureBasePtr _capture)
}
ProcessorBasePtr ProcessorRangeBearing::create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params,
const SensorBasePtr _sen_ptr)
const ProcessorParamsBasePtr _params)
{
auto params = std::static_pointer_cast<ProcessorParamsRangeBearing>(_params);
......
......@@ -51,9 +51,8 @@ class ProcessorRangeBearing : public ProcessorBase
// Factory method for high level API
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params,
const SensorBasePtr sensor_ptr = nullptr);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorRangeBearing, ProcessorParamsRangeBearing, SensorRangeBearing);
const ProcessorParamsBasePtr _params);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorRangeBearing, ProcessorParamsRangeBearing);
protected:
// Implementation of pure virtuals from ProcessorBase
......
......@@ -167,8 +167,7 @@ namespace wolf
typedef Factory<ProcessorBase,
const std::string&,
const ParamsServer&,
const SensorBasePtr> AutoConfProcessorFactory;
const ParamsServer&> AutoConfProcessorFactory;
template<>
inline std::string AutoConfProcessorFactory::getClass()
{
......
......@@ -30,10 +30,9 @@ namespace wolf {
*
* ProcessorClass(const SensorClassPtr _sensor, const ProcessorParamsClassPtr _params);
*/
#define WOLF_CREATE_PROCESSOR_AUTO(ProcessorClass, ProcessorParamsClass, SensorClass) \
#define WOLF_CREATE_PROCESSOR_AUTO(ProcessorClass, ProcessorParamsClass) \
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, \
const ParamsServer& _server, \
const SensorBasePtr _sensor) \
const ParamsServer& _server) \
{ \
auto params = std::make_shared<ProcessorParamsClass>(_unique_name, _server); \
\
......
......@@ -34,8 +34,8 @@ class ProcessorDiffDrive : public ProcessorOdom2D
{
public:
ProcessorDiffDrive(ProcessorParamsDiffDrivePtr _params_motion);
static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr);
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr = nullptr);
static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params);
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server);
virtual ~ProcessorDiffDrive();
protected:
......
......@@ -167,8 +167,7 @@ namespace wolf
typedef Factory<ProcessorBase,
const std::string&,
const ProcessorParamsBasePtr,
const SensorBasePtr> ProcessorFactory;
const ProcessorParamsBasePtr> ProcessorFactory;
template<>
inline std::string ProcessorFactory::getClass()
{
......
......@@ -94,8 +94,8 @@ class ProcessorOdom2D : public ProcessorMotion
// Factory method
public:
static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr);
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr sensor_ptr = nullptr);
static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params);
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, const ParamsServer& _server);
};
inline Eigen::VectorXs ProcessorOdom2D::deltaZero() const
......
......@@ -129,8 +129,7 @@ class ProcessorOdom3D : public ProcessorMotion
// Factory method
public:
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params,
const SensorBasePtr sensor_ptr = nullptr);
const ProcessorParamsBasePtr _params);
};
inline Eigen::VectorXs ProcessorOdom3D::deltaZero() const
......
......@@ -177,7 +177,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
return ProcessorBasePtr();
}
ProcessorBasePtr prc_ptr = ProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _prc_params, _corresponding_sensor_ptr);
ProcessorBasePtr prc_ptr = ProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _prc_params);
prc_ptr->configure(_corresponding_sensor_ptr);
prc_ptr->link(_corresponding_sensor_ptr);
......@@ -218,7 +218,7 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
SensorBasePtr sen_ptr = getSensor(_corresponding_sensor_name);
if (sen_ptr == nullptr)
throw std::runtime_error("Cannot bind processor. Reason: Sensor \"" + _corresponding_sensor_name + "\" not found. Check sensor name, in must match in sensor and processor!");
ProcessorBasePtr prc_ptr = AutoConfProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _server, sen_ptr);
ProcessorBasePtr prc_ptr = AutoConfProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _server);
prc_ptr->configure(sen_ptr);
prc_ptr->link(sen_ptr);
......
......@@ -31,18 +31,18 @@ ProcessorDiffDrive::~ProcessorDiffDrive()
//
}
ProcessorBasePtr ProcessorDiffDrive::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr)
ProcessorBasePtr ProcessorDiffDrive::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
{
ProcessorDiffDrivePtr prc_ptr;
// ProcessorDiffDrivePtr prc_ptr;
std::shared_ptr<ProcessorParamsDiffDrive> params;
if (_params)
params = std::static_pointer_cast<ProcessorParamsDiffDrive>(_params);
else
params = std::make_shared<ProcessorParamsDiffDrive>();
// std::shared_ptr<ProcessorParamsDiffDrive> params;
// if (_params)
auto params = std::static_pointer_cast<ProcessorParamsDiffDrive>(_params);
// else
// params = std::make_shared<ProcessorParamsDiffDrive>();
prc_ptr = std::make_shared<ProcessorDiffDrive>(params);
auto prc_ptr = std::make_shared<ProcessorDiffDrive>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
......@@ -185,7 +185,7 @@ FactorBasePtr ProcessorDiffDrive::emplaceFactor(FeatureBasePtr _feature,
///////////// FACTORIES ///////////////
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)
{
auto params = std::make_shared<ProcessorParamsDiffDrive>(_unique_name, _server);
......
......@@ -167,28 +167,23 @@ FeatureBasePtr ProcessorOdom2D::emplaceFeature(CaptureMotionPtr _capture_motion)
return key_feature_ptr;
}
ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr)
ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
{
auto params = std::static_pointer_cast<ProcessorParamsOdom2D>(_params);
ProcessorOdom2DPtr prc_ptr;
std::shared_ptr<ProcessorParamsOdom2D> params;
if (_params)
params = std::static_pointer_cast<ProcessorParamsOdom2D>(_params);
else
params = std::make_shared<ProcessorParamsOdom2D>();
auto prc_ptr = std::make_shared<ProcessorOdom2D>(params);
prc_ptr = std::make_shared<ProcessorOdom2D>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
}
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)
{
auto params = std::make_shared<ProcessorParamsOdom2D>(_unique_name, _server);
auto prc_ptr = std::make_shared<ProcessorOdom2D>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
......
......@@ -333,7 +333,7 @@ Motion ProcessorOdom3D::interpolate(const Motion& _ref1,
}
ProcessorBasePtr ProcessorOdom3D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr _sen_ptr)
ProcessorBasePtr ProcessorOdom3D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
{
// cast inputs to the correct type
auto params = std::static_pointer_cast<ProcessorParamsOdom3D>(_params);
......
......@@ -93,16 +93,16 @@ FactorBasePtr ProcessorTrackerFeatureDummy::emplaceFactor(FeatureBasePtr _featur
}
ProcessorBasePtr ProcessorTrackerFeatureDummy::create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params,
const SensorBasePtr)
const ProcessorParamsBasePtr _params)
{
ProcessorParamsTrackerFeatureDummyPtr params = std::static_pointer_cast<ProcessorParamsTrackerFeatureDummy>(_params);
auto params = std::static_pointer_cast<ProcessorParamsTrackerFeatureDummy>(_params);
// if cast failed use default value
if (params == nullptr)
params = std::make_shared<ProcessorParamsTrackerFeatureDummy>();
ProcessorTrackerFeatureDummyPtr prc_ptr = std::make_shared<ProcessorTrackerFeatureDummy>(params);
auto prc_ptr = std::make_shared<ProcessorTrackerFeatureDummy>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
......
......@@ -105,8 +105,7 @@ class ProcessorTrackerFeatureDummy : public ProcessorTrackerFeature
public:
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params,
const SensorBasePtr sensor_ptr = nullptr);
const ProcessorParamsBasePtr _params);
};
......
......@@ -205,6 +205,7 @@ TEST(Odom2D, VoteForKfAndSolve)
ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);
// NOTE: We integrate and create KFs as follows:
// i= 0 1 2 3 4 5 6
// KF -- * -- * -- KF - * -- * -- KF - *
......
......@@ -167,7 +167,7 @@ TEST(ProcessorDiffDrive, create)
auto params = std::make_shared<ProcessorParamsDiffDrive>();
// processor
auto prc_base = ProcessorDiffDrive::create("prc", params, sen);
auto prc_base = ProcessorDiffDrive::create("prc", params);
auto prc = std::static_pointer_cast<ProcessorDiffDrive>(prc_base);
......
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