11 namespace mrpt {
namespace graphslam {
13 template<
class GRAPH_t>
16 const std::string& config_file,
17 const std::string& rawlog_fname,
18 const std::string& fname_GT ,
36 template<
class GRAPH_t>
42 template<
class GRAPH_t>
81 template<
class GRAPH_t>
87 template<
class GRAPH_t>
90 template<
class GRAPH_t>
92 mrpt::obs::CActionCollection::Ptr& action,
93 mrpt::obs::CSensoryFrame::Ptr& observations,
94 mrpt::obs::CObservation::Ptr& observation,
95 size_t& rawlog_entry) {
98 action, observations, observation, rawlog_entry);
101 return continue_exec;
104 template<
class GRAPH_t>
107 template<
class GRAPH_t>
110 "Setting up subscribers, publishers, services...");
119 template<
class GRAPH_t>
125 template<
class GRAPH_t>
131 template<
class GRAPH_t>
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_t > * m_node_reg
virtual ~CGraphSlamEngine_ROS()
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_t > * m_edge_reg
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
CGraphSlamEngine_ROS(ros::NodeHandle *nh, const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_t > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_t > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_t > *optimizer=NULL)
void readParams()
Read the problem configuration parameters.
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
virtual void usePublishersBroadcasters()
Provide feedback about the SLAM operation.
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_t > * m_optimizer
ROSCPP_DECL void shutdown()
Interface class that all ROS-specific deciders/optimizers can inherit from.
void initClass()
Initialize object instance.
void readROSParameters()
Read configuration parameters from the ROS parameter server.
void setupComm()
Wrapper method around the protected setup* class methods.
virtual void setNodeHandle(ros::NodeHandle *nh)
virtual bool _execGraphSlamStep(mrpt::obs::CActionCollectionPtr &action, mrpt::obs::CSensoryFramePtr &observations, mrpt::obs::CObservationPtr &observation, size_t &rawlog_entry)