Skip to content
Snippets Groups Projects
Commit 12bffb24 authored by Timothy Wiley's avatar Timothy Wiley
Browse files

crosbot_fastslam: make sub/pub topics configurable

parent d42cb7c4
Branches
No related tags found
No related merge requests found
......@@ -34,7 +34,11 @@ protected:
std::string baseFrame;
std::string mapFrame;
std::string odomFrame;
std::string pubParticles;
std::string pub_historyName;
std::string pub_mapName;
std::string pub_particlesName;
std::string sub_scanName;
std::string sub_snapName;
ros::Subscriber scanSub;
ros::Subscriber snapSub;
......
......@@ -68,14 +68,18 @@ void FastSLAMModule::initialize(ros::NodeHandle& nh) {
paramNH.param<std::string>("base_frame", baseFrame, DEFAULT_BASEFRAME);
paramNH.param<std::string>("map_frame", mapFrame, DEFAULT_MAPFRAME);
paramNH.param<std::string>("odom_frame", odomFrame, DEFAULT_ODOMFRAME);
paramNH.param<std::string>("pub_particles", pubParticles, "/crosbot_fastslam/particles");
paramNH.param<std::string>("pub_history", pub_historyName, "/crosbot_fastslam/history");
paramNH.param<std::string>("pub_map", pub_mapName, "/crosbot_fastslam/map");
paramNH.param<std::string>("pub_particles", pub_particlesName, "/crosbot_fastslam/particles");
paramNH.param<std::string>("sub_scan", sub_scanName, "/scan");
paramNH.param<std::string>("sub_snap", sub_snapName, "/crosbot_fastslam/snaps");
ROS_INFO("%s map: %s, odom: %s, base: %s", LOG_START, mapFrame.c_str(), odomFrame.c_str(), baseFrame.c_str());
scanSub = nh.subscribe("scan", 1, &FastSLAMModule::callbackScan, this);
snapSub = nh.subscribe("snap", 1000, &FastSLAMModule::callbackSnap, this);
gridPub = nh.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
historyPub = nh.advertise<nav_msgs::Path>("history", 1);
particlesPub = nh.advertise<geometry_msgs::PoseArray>(pubParticles, 1);
scanSub = nh.subscribe(sub_scanName, 1, &FastSLAMModule::callbackScan, this);
snapSub = nh.subscribe(sub_snapName, 1000, &FastSLAMModule::callbackSnap, this);
gridPub = nh.advertise<nav_msgs::OccupancyGrid>(pub_mapName, 1, true);
historyPub = nh.advertise<nav_msgs::Path>(pub_historyName, 1);
particlesPub = nh.advertise<geometry_msgs::PoseArray>(pub_particlesName, 1);
// read configuration/parameters
ConfigElementPtr config = new ROSConfigElement(paramNH);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment