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

Add create() to the macro; rename to WOLF_PROCESSOR_CREATE

parent 72a61f2a
No related branches found
No related tags found
1 merge request!313WIP: Resolve "Processor constructors and creators requiring a sensor pointer?"
Pipeline #4169 passed
......@@ -99,19 +99,6 @@ void ProcessorRangeBearing::processCapture(CaptureBasePtr _capture)
}
ProcessorBasePtr ProcessorRangeBearing::create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params)
{
auto params = std::static_pointer_cast<ProcessorParamsRangeBearing>(_params);
// construct processor
auto prc = std::make_shared<ProcessorRangeBearing>(params);
// setup processor
prc->setName(_unique_name);
return prc;
}
Eigen::Vector2s ProcessorRangeBearing::observe(const Eigen::Vector2s& lmk_w) const
{
......
......@@ -50,9 +50,7 @@ class ProcessorRangeBearing : public ProcessorBase
virtual void configure(SensorBasePtr _sensor) override;
// Factory method for high level API
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorRangeBearing, ProcessorParamsRangeBearing);
WOLF_PROCESSOR_CREATE(ProcessorRangeBearing, ProcessorParamsRangeBearing);
protected:
// Implementation of pure virtuals from ProcessorBase
......
......@@ -28,20 +28,30 @@ namespace wolf {
* In order to use this macro, the derived processor class, ProcessorClass,
* must have a constructor available with the API:
*
* ProcessorClass(const SensorClassPtr _sensor, const ProcessorParamsClassPtr _params);
* ProcessorClass(const ProcessorParamsClassPtr _params);
*/
#define WOLF_CREATE_PROCESSOR_AUTO(ProcessorClass, ProcessorParamsClass) \
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, \
const ParamsServer& _server) \
{ \
auto params = std::make_shared<ProcessorParamsClass>(_unique_name, _server); \
\
auto processor = std::make_shared<ProcessorClass>(params); \
\
processor ->setName(_unique_name); \
\
return processor; \
}
#define WOLF_PROCESSOR_CREATE(ProcessorClass, ProcessorParamsClass) \
static ProcessorBasePtr createAutoConf(const std::string& _unique_name, \
const ParamsServer& _server) \
{ \
auto params = std::make_shared<ProcessorParamsClass>(_unique_name, _server); \
\
auto processor = std::make_shared<ProcessorClass>(params); \
\
processor ->setName(_unique_name); \
\
return processor; \
} \
static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params) \
{ \
auto params = std::static_pointer_cast<ProcessorParamsClass>(_params); \
\
auto processor = std::make_shared<ProcessorClass>(params); \
\
processor ->setName(_unique_name); \
\
return processor; \
} \
......
......@@ -38,9 +38,7 @@ class ProcessorDiffDrive : public ProcessorOdom2D
virtual void configure(SensorBasePtr _sensor) override;
// Factory method for high level API
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorDiffDrive, ProcessorParamsDiffDrive);
WOLF_PROCESSOR_CREATE(ProcessorDiffDrive, ProcessorParamsDiffDrive);
protected:
// Motion integration
......
......@@ -45,9 +45,7 @@ class ProcessorOdom2D : public ProcessorMotion
virtual void configure(SensorBasePtr _sensor) override { };
// Factory method for high level API
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorOdom2D, ProcessorParamsOdom2D);
WOLF_PROCESSOR_CREATE(ProcessorOdom2D, ProcessorParamsOdom2D);
virtual bool voteForKeyFrame() override;
......
......@@ -65,9 +65,7 @@ class ProcessorOdom3D : public ProcessorMotion
virtual void configure(SensorBasePtr _sensor) override;
// Factory method for high level API
static ProcessorBasePtr create(const std::string& _unique_name,
const ProcessorParamsBasePtr _params);
WOLF_CREATE_PROCESSOR_AUTO(ProcessorOdom3D, ProcessorParamsOdom3D);
WOLF_PROCESSOR_CREATE(ProcessorOdom3D, ProcessorParamsOdom3D);
public:
// Motion integration
......
......@@ -31,16 +31,6 @@ ProcessorDiffDrive::~ProcessorDiffDrive()
//
}
ProcessorBasePtr ProcessorDiffDrive::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
{
auto params = std::static_pointer_cast<ProcessorParamsDiffDrive>(_params);
auto prc_ptr = std::make_shared<ProcessorDiffDrive>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
}
void ProcessorDiffDrive::configure(SensorBasePtr _sensor)
{
......
......@@ -167,16 +167,6 @@ FeatureBasePtr ProcessorOdom2D::emplaceFeature(CaptureMotionPtr _capture_motion)
return key_feature_ptr;
}
ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params)
{
auto params = std::static_pointer_cast<ProcessorParamsOdom2D>(_params);
auto prc_ptr = std::make_shared<ProcessorOdom2D>(params);
prc_ptr->setName(_unique_name);
return prc_ptr;
}
} /* namespace wolf */
......
......@@ -333,19 +333,6 @@ Motion ProcessorOdom3D::interpolate(const Motion& _ref1,
}
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);
// construct processor
auto prc_odo = std::make_shared<ProcessorOdom3D>(params);
// setup processor
prc_odo->setName(_unique_name);
return prc_odo;
}
bool ProcessorOdom3D::voteForKeyFrame()
{
......
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