mrpt_graphslam_2d_node.cpp
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+
9  */
10 
11 // MRPT headers
12 #include <mrpt/system/COutputLogger.h>
13 #include <mrpt/graphslam/CGraphSlamEngine.h>
14 #include <mrpt/system/string_utils.h>
15 
16 #include <cstdlib>
17 #include <cstring>
18 
19 // ROS headers
21 
22 using namespace mrpt;
23 using namespace mrpt::poses;
24 using namespace mrpt::obs;
25 using namespace mrpt::system;
26 using namespace mrpt::graphs;
27 using namespace mrpt::math;
28 using namespace mrpt::opengl;
29 using namespace mrpt::graphslam;
30 using namespace mrpt::graphslam::deciders;
31 using namespace mrpt::graphslam::optimizers;
32 using namespace mrpt::graphslam::apps;
33 
34 using namespace std;
35 
37 int main(int argc, char** argv)
38 {
39  std::string node_name = "mrpt_graphslam_2d";
40 
41  COutputLogger logger;
42  logger.setLoggerName(node_name);
43  logger.logFmt(LVL_WARN, "Initializing %s node...\n", node_name.c_str());
44 
45  ros::init(argc, argv, node_name);
46  ros::NodeHandle nh;
47 
48  ros::Rate loop_rate(10);
49 
50  try
51  {
52  // Initialization
55  &logger, &options_checker, &nh);
56  graphslam_handler.readParams();
57  graphslam_handler.initEngine_ROS();
58  graphslam_handler.setupComm();
59 
60  // print the parameters just for verification
61  graphslam_handler.printParams();
62 
63  bool cont_exec = true;
64  while (ros::ok() && cont_exec)
65  {
66  cont_exec = graphslam_handler.usePublishersBroadcasters();
67 
68  ros::spinOnce();
69  loop_rate.sleep();
70  }
71  }
72  catch (exception& e)
73  {
75  "Finished with a (known) exception!" << std::endl
76  << e.what() << std::endl);
77  mrpt::system::pause();
78  return -1;
79  }
80  catch (...)
81  {
82  ROS_ERROR_STREAM("Finished with a (unknown) exception!" << std::endl);
83  mrpt::system::pause();
84  return -1;
85  }
86 }
mrpt::graphslam::apps::CGraphSlamHandler_ROS::readParams
void readParams()
Read the problem configuration parameters.
Definition: CGraphSlamHandler_ROS_impl.h:78
mrpt::graphslam::apps::TUserOptionsChecker_ROS
Definition: TUserOptionsChecker_ROS.h:23
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
mrpt::graphslam::apps::CGraphSlamHandler_ROS::printParams
void printParams()
Print in a compact manner the overall problem configuration parameters.
Definition: CGraphSlamHandler_ROS_impl.h:262
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
mrpt::graphslam::apps::CGraphSlamHandler_ROS
Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper.
Definition: CGraphSlamHandler_ROS.h:65
mrpt::graphslam::apps::CGraphSlamHandler_ROS::initEngine_ROS
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
Definition: CGraphSlamHandler_ROS_impl.h:163
ros::spinOnce
ROSCPP_DECL void spinOnce()
mrpt
Definition: CConnectionManager.h:31
ros::ok
ROSCPP_DECL bool ok()
rename_rviz_topics.logger
logger
Definition: rename_rviz_topics.py:31
mrpt::graphslam::apps
Definition: CGraphSlamHandler_ROS.h:59
mrpt::graphslam
Definition: CConnectionManager.h:33
main
int main(int argc, char **argv)
Definition: mrpt_graphslam_2d_node.cpp:37
mrpt::graphslam::optimizers
Definition: CGraphSlamOptimizer_MR_impl.h:12
ros::Rate::sleep
bool sleep()
mrpt::graphslam::apps::CGraphSlamHandler_ROS::usePublishersBroadcasters
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
Definition: CGraphSlamHandler_ROS_impl.h:432
CGraphSlamHandler_ROS.h
std
mrpt::graphslam::apps::CGraphSlamHandler_ROS::setupComm
void setupComm()
Wrapper method around the protected setup* class methods.
Definition: CGraphSlamHandler_ROS_impl.h:335
mrpt::math
Definition: CGraphSlamEngine_MR_impl.h:19
ros::Rate
mrpt::graphslam::deciders
Definition: CLoopCloserERD_MR.h:22
ros::NodeHandle


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31