Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #pragma once
00011 namespace mrpt { namespace graphslam {
00012
00013 template<class GRAPH_t>
00014 CGraphSlamEngine_ROS<GRAPH_t>::CGraphSlamEngine_ROS(
00015 ros::NodeHandle* nh,
00016 const std::string& config_file,
00017 const std::string& rawlog_fname,
00018 const std::string& fname_GT ,
00019 mrpt::graphslam::CWindowManager* win_manager ,
00020 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_t>* node_reg ,
00021 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_t>* edge_reg ,
00022 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_t>* optimizer ):
00023 parent::CGraphSlamEngine(
00024 config_file,
00025 rawlog_fname,
00026 fname_GT,
00027 win_manager,
00028 node_reg,
00029 edge_reg,
00030 optimizer),
00031 m_nh(nh)
00032 {
00033 this->initClass();
00034 }
00035
00036 template<class GRAPH_t>
00037 CGraphSlamEngine_ROS<GRAPH_t>::~CGraphSlamEngine_ROS() {
00038 MRPT_LOG_DEBUG_STREAM("In Destructor: Deleting CGraphSlamEngine_ROS instance...");
00039 ros::shutdown();
00040 }
00041
00042 template<class GRAPH_t>
00043 void CGraphSlamEngine_ROS<GRAPH_t>::initClass() {
00044 using namespace mrpt::graphslam;
00045 this->m_class_name = "CGraphSlamEngine_ROS";
00046 this->setLoggerName(this->m_class_name);
00047
00048
00049 m_queue_size = 10;
00050
00051 this->setupComm();
00052
00053
00054
00055 {
00056 CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>* dec_opt_ros =
00057 dynamic_cast<CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>*>(this->m_node_reg);
00058
00059 if (dec_opt_ros) {
00060 dec_opt_ros->setNodeHandle(m_nh);
00061 }
00062 }
00063 {
00064 CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>* dec_opt_ros =
00065 dynamic_cast<CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>*>(this->m_edge_reg);
00066 if (dec_opt_ros) {
00067 dec_opt_ros->setNodeHandle(m_nh);
00068 }
00069 }
00070 {
00071 CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>* dec_opt_ros =
00072 dynamic_cast<CRegistrationDeciderOrOptimizer_ROS<GRAPH_t>*>(this->m_optimizer);
00073 if (dec_opt_ros) {
00074 dec_opt_ros->setNodeHandle(m_nh);
00075 }
00076 }
00077
00078 this->readParams();
00079 }
00080
00081 template<class GRAPH_t>
00082 void CGraphSlamEngine_ROS<GRAPH_t>::readParams() {
00083
00084 this->readROSParameters();
00085 }
00086
00087 template<class GRAPH_t>
00088 void CGraphSlamEngine_ROS<GRAPH_t>::readROSParameters() { }
00089
00090 template<class GRAPH_t>
00091 bool CGraphSlamEngine_ROS<GRAPH_t>::_execGraphSlamStep(
00092 mrpt::obs::CActionCollection::Ptr& action,
00093 mrpt::obs::CSensoryFrame::Ptr& observations,
00094 mrpt::obs::CObservation::Ptr& observation,
00095 size_t& rawlog_entry) {
00096
00097 bool continue_exec = parent::_execGraphSlamStep(
00098 action, observations, observation, rawlog_entry);
00099 this->usePublishersBroadcasters();
00100
00101 return continue_exec;
00102 }
00103
00104 template<class GRAPH_t>
00105 void CGraphSlamEngine_ROS<GRAPH_t>::usePublishersBroadcasters() { }
00106
00107 template<class GRAPH_t>
00108 void CGraphSlamEngine_ROS<GRAPH_t>::setupComm() {
00109 MRPT_LOG_INFO_STREAM(
00110 "Setting up subscribers, publishers, services...");
00111
00112
00113 this->setupSubs();
00114 this->setupPubs();
00115 this->setupSrvs();
00116
00117 }
00118
00119 template<class GRAPH_t>
00120 void CGraphSlamEngine_ROS<GRAPH_t>::setupSubs() {
00121 MRPT_LOG_DEBUG_STREAM("Setting up subscribers...");
00122
00123 }
00124
00125 template<class GRAPH_t>
00126 void CGraphSlamEngine_ROS<GRAPH_t>::setupPubs() {
00127 MRPT_LOG_DEBUG_STREAM("Setting up publishers...");
00128
00129 }
00130
00131 template<class GRAPH_t>
00132 void CGraphSlamEngine_ROS<GRAPH_t>::setupSrvs() {
00133 MRPT_LOG_DEBUG_STREAM("Setting up services...");
00134
00135 }
00136
00137
00138 } }
00139