11 namespace mrpt {
namespace graphslam {
namespace apps {
14 template<
class GRAPH_T>
17 template<
class GRAPH_T>
21 template<
class GRAPH_T>
23 mrpt::utils::COutputLogger*
logger,
24 TUserOptionsChecker<GRAPH_T>* options_checker,
26 parent_t(logger, options_checker, false),
55 template<
class GRAPH_T>
58 template<
class GRAPH_T>
62 ASSERT_(!this->m_ini_fname.empty());
63 parent_t::readConfigFname(this->m_ini_fname);
67 template<
class GRAPH_T>
73 std::string ns =
"misc/";
76 bool m_disable_MRPT_visuals;
77 m_nh->
param<
bool>(ns +
"disable_MRPT_visuals", m_disable_MRPT_visuals,
false);
78 this->m_enable_visuals = !m_disable_MRPT_visuals;
84 static_cast<int>(LVL_INFO));
90 std::string ns =
"deciders_optimizers/";
97 std::string ns =
"files/";
100 std::string config_param_path = ns +
"config";
101 bool found_config =
m_nh->
getParam(ns +
"config", this->m_ini_fname);
102 ASSERTMSG_(found_config,
104 "Configuration file was not set. Set %s and try again.\nExiting...",
105 config_param_path.c_str()));
114 std::string ns =
"frame_IDs/";
124 this->m_options_checker->createDeciderOptimizerMappings();
125 this->m_options_checker->populateDeciderOptimizerProperties();
128 this->m_logger->logFmt(LVL_DEBUG,
129 "Successfully read parameters from ROS Parameter Server");
132 if (this->m_enable_visuals) {
133 this->initVisualization();
137 template<
class GRAPH_T>
140 template<
class GRAPH_T>
143 this->m_logger->logFmt(LVL_WARN,
144 "Initializing CGraphSlamEngine_ROS instance...");
151 this->m_options_checker->node_regs_map[
m_node_reg](),
152 this->m_options_checker->edge_regs_map[
m_edge_reg](),
153 this->m_options_checker->optimizers_map[
m_optimizer]());
154 this->m_logger->logFmt(LVL_WARN,
155 "Successfully initialized CGraphSlamEngine_ROS instance.");
159 template<
class GRAPH_T>
162 this->m_options_checker->node_regs_map[
m_node_reg]();
163 this->m_options_checker->edge_regs_map[
m_edge_reg]();
164 this->m_options_checker->optimizers_map[
m_optimizer]();
166 this->m_logger->logFmt(LVL_WARN,
167 "Initializing CGraphSlamEngine_MR instance...");
174 this->m_options_checker->node_regs_map[
m_node_reg](),
175 this->m_options_checker->edge_regs_map[
m_edge_reg](),
176 this->m_options_checker->optimizers_map[
m_optimizer]());
177 this->m_logger->logFmt(LVL_WARN,
178 "Successfully initialized CGraphSlamEngine_MR instance.");
182 template<
class GRAPH_T>
192 ss <<
"ROS Parameters: " << endl;
196 ss <<
"Deciders / Optimizers = " << endl;
198 ss <<
"Node Registration Decider = " <<
m_node_reg << endl;
199 ss <<
"Edge Registration Decider = " <<
m_edge_reg << endl;
200 ss <<
"GraphSLAM Optimizer = " <<
m_optimizer << endl;
203 ss <<
"Filenames: " << endl;
205 ss <<
"Configuration .ini file = " << this->m_ini_fname << endl;
206 ss <<
"Ground truth filename = " << (!this->m_gt_fname.empty()
207 ? this->m_gt_fname :
"NONE")
211 ss <<
"Miscellaneous: " << endl;
213 ss <<
"Enable MRPT visuals? = " <<
214 (this->m_enable_visuals?
"TRUE" :
"FALSE")
216 ss <<
"Logging verbosity Level = " <<
217 COutputLogger::logging_levels_to_names
218 #if MRPT_VERSION>=0x199 227 template<
class GRAPH_T>
232 std::string ros_params(
"");
234 std::string mrpt_params(
"");
235 parent_t::getParamsAsString(&mrpt_params);
237 *str_out += ros_params;
239 *str_out += mrpt_params;
244 template<
class GRAPH_T>
251 template<
class GRAPH_T>
254 parent_t::printParams();
260 template<
class GRAPH_T>
262 this->m_logger->logFmt(LVL_DEBUG,
"Verifying user input...");
266 bool node_success, edge_success, optimizer_success;
270 this->m_options_checker->checkRegistrationDeciderExists(
273 this->m_options_checker->checkRegistrationDeciderExists(
276 this->m_options_checker->checkOptimizerExists(
280 this->m_logger->logFmt(LVL_ERROR,
281 "\nNode Registration Decider \"%s\" is not available",
283 this->m_options_checker->dumpRegistrarsToConsole(
"node");
287 this->m_logger->logFmt(LVL_ERROR,
288 "\nEdge Registration Decider \"%s\" is not available.",
290 this->m_options_checker->dumpRegistrarsToConsole(
"edge");
293 if (!optimizer_success) {
294 this->m_logger->logFmt(LVL_ERROR,
295 "\ngraphSLAM Optimizser \"%s\" is not available.",
297 this->m_options_checker->dumpOptimizersToConsole();
304 bool ini_exists = system::fileExists(this->m_ini_fname);
305 ASSERTMSG_(ini_exists,
307 "\n.ini configuration file \"%s\"doesn't exist. " 308 "Please specify a valid pathname.\nExiting...\n",
309 this->m_ini_fname.c_str()));
311 if (!this->m_gt_fname.empty()) {
312 bool gt_exists = system::fileExists(this->m_gt_fname);
313 ASSERTMSG_(gt_exists,
315 "\nGround truth file \"%s\"doesn't exist." 316 "Either unset the corresponding ROS parameter or specify a valid pathname.\n" 318 this->m_gt_fname.c_str()));
323 template<
class GRAPH_T>
326 this->m_logger->logFmt(LVL_INFO,
327 "Setting up ROS-related subscribers, publishers, services...");
339 template<
class GRAPH_T>
341 this->m_logger->logFmt(LVL_INFO,
"Setting up the subscribers...");
344 std::string ns =
"input/";
369 template<
class GRAPH_T>
371 this->m_logger->logFmt(LVL_INFO,
"Setting up the publishers...");
374 std::string ns =
"feedback/";
418 template<
class GRAPH_T>
420 this->m_logger->logFmt(LVL_INFO,
"Setting up the services...");
426 template<
class GRAPH_T>
437 pose_t mrpt_pose = this->m_engine->getCurrentRobotPosEstimation();
443 geometry_msgs::TransformStamped anchor_base_link_transform;
449 anchor_base_link_transform.transform.translation.x = mrpt_pose.x();
450 anchor_base_link_transform.transform.translation.y = mrpt_pose.y();
451 anchor_base_link_transform.transform.translation.z = 0;
454 anchor_base_link_transform.transform.rotation =
471 geometry_msgs::PoseStamped geom_pose;
472 geom_pose.header.stamp = timestamp;
477 mrpt_bridge::convert(mrpt_pose, geom_pose.pose);
484 this->m_logger->logFmt(LVL_DEBUG,
485 "Publishing the current robot trajectory");
486 typename GRAPH_T::global_poses_t graph_poses;
487 #if MRPT_VERSION>=0x199 488 graph_poses = this->m_engine->getRobotEstimatedTrajectory();
490 this->m_engine->getRobotEstimatedTrajectory(&graph_poses);
496 path.header.stamp = timestamp;
504 geometry_msgs::PoseArray geom_poses;
505 geom_poses.header.stamp = timestamp;
508 for (
auto n_cit = graph_poses.begin();
509 n_cit != graph_poses.end();
512 geometry_msgs::PoseStamped geom_pose_stamped;
513 geometry_msgs::Pose geom_pose;
516 const pose_t& mrpt_pose = n_cit->second;
517 mrpt_bridge::convert(mrpt_pose, geom_pose);
518 geom_poses.poses.push_back(geom_pose);
519 geom_pose_stamped.pose = geom_pose;
522 geom_pose_stamped.header.stamp = timestamp;
523 geom_pose_stamped.header.seq =
m_pub_seq;
526 path.poses.push_back(geom_pose_stamped);
543 mrpt::system::TTimeStamp mrpt_time;
544 mrpt::maps::COccupancyGridMap2D::Ptr mrpt_gridmap =
545 mrpt::maps::COccupancyGridMap2D::Create();
546 this->m_engine->getMap(mrpt_gridmap, &mrpt_time);
549 mrpt_bridge::convert(mrpt_time, h.stamp);
554 nav_msgs::OccupancyGrid nav_gridmap;
555 mrpt_bridge::convert(*mrpt_gridmap, nav_gridmap, h);
561 mrpt_msgs::GraphSlamStats stats;
564 map<string, int> node_stats;
565 map<string, int> edge_stats;
566 vector<double> def_energy_vec;
567 mrpt::system::TTimeStamp mrpt_time;
569 this->m_engine->getGraphSlamStats(&node_stats,
574 stats.nodes_total = node_stats[
"nodes_total"];
575 stats.edges_total = edge_stats[
"edges_total"];
576 if (edge_stats.find(
"ICP2D") != edge_stats.end()) {
577 stats.edges_ICP2D = edge_stats[
"ICP2D"];
579 if (edge_stats.find(
"ICP3D") != edge_stats.end()) {
580 stats.edges_ICP3D = edge_stats[
"ICP3D"];
582 if (edge_stats.find(
"Odometry") != edge_stats.end()) {
583 stats.edges_odom = edge_stats[
"Odometry"];
585 stats.loop_closures = edge_stats[
"loop_closures"];
588 this->m_engine->getDeformationEnergyVector(
589 &stats.slam_evaluation_metric);
591 mrpt_bridge::convert(mrpt_time, stats.header.stamp);
603 if (this->m_enable_visuals) {
604 ret_val = this->queryObserverForEvents();
611 template<
class GRAPH_T>
613 const sensor_msgs::LaserScan::ConstPtr& ros_laser_scan) {
618 this->m_logger->logFmt(
620 "sniffLaserScan: Received a LaserScan msg. Converting it to MRPT format...");
624 mrpt::poses::CPose3D rel_pose;
632 template<
class GRAPH_T>
634 const nav_msgs::Odometry::ConstPtr& ros_odom) {
640 this->m_logger->logFmt(
642 "sniffOdom: Received an odometry msg. Converting it to MRPT format...");
659 ros_odom->pose.pose.position.x;
661 ros_odom->pose.pose.position.y;
663 ros_odom->pose.pose.position.z;
667 ros_odom->pose.pose.orientation;
672 mrpt_bridge::convert(
673 ros_odom->header.stamp,
675 mrpt_bridge::convert(
691 geometry_msgs::PoseStamped pose_stamped;
692 pose_stamped.header = ros_odom->header;
695 mrpt_bridge::convert(
703 ss <<
"Odometry - MRPT format:\t" <<
m_mrpt_odom->odometry << endl;
704 this->m_logger->logFmt(LVL_DEBUG,
"%s", ss.str().c_str());
707 CObservation::Ptr tmp = mrpt::ptr_cast<mrpt::obs::CObservation>::from(
m_mrpt_odom);
711 template<
class GRAPH_T>
713 THROW_EXCEPTION(
"Method is not implemented yet.");
716 template<
class GRAPH_T>
718 THROW_EXCEPTION(
"Method is not implemented yet.");
721 template<
class GRAPH_T>
723 mrpt::obs::CObservation::Ptr& observ) {
732 template<
class GRAPH_T>
734 mrpt::obs::CObservation::Ptr& observ) {
740 if (!this->m_engine->isPaused()) {
746 template<
class GRAPH_T>
void readROSParameters()
read configuration parameters from the ROS parameter server.
void readParams()
Read the problem configuration parameters.
void verifyUserInput()
Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance...
tf2_ros::TransformBroadcaster m_broadcaster
pose_t m_input_odometry_offset
void publish(const boost::shared_ptr< M > &message) const
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
CGraphSlamHandler_ROS(mrpt::utils::COutputLogger *logger, TUserOptionsChecker< GRAPH_T > *options_checker, ros::NodeHandle *nh_in)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
std::string getParamsAsString()
bool m_first_time_in_sniff_odom
Initial offset of the received odometry.
ros::Subscriber m_laser_scan_sub
static const std::string sep_subheader
std::string m_curr_robot_pos_topic
size_t m_measurement_cnt
Total counter of the processed measurements.
mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
ros::Subscriber m_odom_sub
bool m_received_laser_scan
VerbosityLevel m_min_logging_level
Minimum logging level for the current class instance.
ros::Publisher m_robot_tr_poses_pub
static const std::string sep_header
std::string m_base_link_frame_id
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
geometry_msgs::TransformStamped m_anchor_odom_transform
ros::NodeHandle * m_nh
Pointer to the Ros NodeHanle instance.
void sniffOdom(const nav_msgs::Odometry::ConstPtr &ros_odom)
Callback method for handling incoming odometry measurements in a ROS topic.
std::string m_odom_frame_id
CGraphSlamHandler< GRAPH_T > parent_t
Handy parent type.
void _process(mrpt::obs::CObservation::Ptr &observ)
Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.
void sniffLaserScan(const sensor_msgs::LaserScan::ConstPtr &ros_laser_scan)
Callback method for handling incoming LaserScans objects in a ROS topic.
ros::Publisher m_odom_trajectory_pub
void setupComm()
Wrapper method around the protected setup* class methods.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void getROSParameters(std::string *str_out)
Fill in the given string with the parameters that have been read from the ROS parameter server...
size_t m_graph_nodes_last_size
std::string m_odom_trajectory_topic
ros::Publisher m_gridmap_pub
nav_msgs::Path m_odom_path
Odometry path of the robot. Handy mostly for visualization reasons.
std::string m_gridmap_topic
std::string m_anchor_frame_id
Frame that the robot starts from. In a single-robot SLAM setup this can be set to the world frame...
std::string m_laser_scan_topic
void printParams()
Print in a compact manner the overall problem configuration parameters.
int m_pub_seq
Times a messge has been published => usePublishersBroadcasters method is called.
ros::Publisher m_curr_robot_pos_pub
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
bool getParam(const std::string &key, std::string &s) const
void resetReceivedFlags()
Reset the flags indicating whether we have received new data (odometry, laser scans etc...
ros::Publisher m_stats_pub
mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom
Received laser scan - converted into MRPT CObservation* format.
void processObservation(mrpt::obs::CObservation::Ptr &observ)
Process an incoming measurement.
std::string m_robot_trajectory_topic
int m_queue_size
ROS topic publisher standard queue size.
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
ros::Publisher m_robot_trajectory_pub
std::string m_robot_tr_poses_topic
std::string m_stats_topic
bool m_received_point_cloud