11 #include <mrpt/utils/COutputLogger.h> 12 #include <mrpt/graphslam/CGraphSlamEngine.h> 13 #include <mrpt/system/string_utils.h> 38 int main(
int argc,
char **argv)
43 std::string node_name =
"mrpt_graphslam_2d_mr";
49 logger.setLoggerName(node_name);
50 logger.logFmt(LVL_WARN,
"Initialized %s node...\n", node_name.c_str());
57 &logger, &options_checker, &nh);
64 graphslam_handler.setResultsDirName(std::string(ns.begin()+2, ns.end()));
69 bool cont_exec =
true;
70 while (
ros::ok() && cont_exec) {
78 catch (exception& e) {
79 cout <<
"Known error!" << endl;
80 logger.logFmt(LVL_ERROR,
"Caught exception: %s", e.what());
81 mrpt::system::pause();
85 cout <<
"Unknown error!" << endl;
86 logger.logFmt(LVL_ERROR,
"Finished with unknown exception. Exiting\n.");
87 mrpt::system::pause();
void readParams()
Read the problem configuration parameters.
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const std::string & getNamespace() const
int main(int argc, char **argv)
void setupComm()
Wrapper method around the protected setup* class methods.
void printParams()
Print in a compact manner the overall problem configuration parameters.
Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper...
ROSCPP_DECL void spinOnce()