38 int main(
int argc,
char **argv)
40 std::string node_name =
"mrpt_graphslam_2d";
43 logger.setLoggerName(node_name);
44 logger.logFmt(LVL_WARN,
"Initializing %s node...\n", node_name.c_str());
57 &logger, &options_checker, &nh);
65 bool cont_exec =
true;
66 while (
ros::ok() && cont_exec) {
73 catch (exception& e) {
75 "Finished with a (known) exception!" 84 "Finished with a (unknown) exception!" void readParams()
Read the problem configuration parameters.
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
void BASE_IMPEXP pause(const std::string &msg=std::string("Press any key to continue...")) MRPT_NO_THROWS
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
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...
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()