Commit 18fe1988 authored by Niklas Yann Wettengel's avatar Niklas Yann Wettengel
Browse files

read scan topic from parameterserver

parent fb17a2c4
......@@ -8,7 +8,9 @@ depth_occupancy_map::depth_occupancy_map(ros::NodeHandle* nh)
{
m_nh = nh;
m_MapSubscriber = nh->subscribe("/map", 1, &depth_occupancy_map::map_callback, this);
m_ScanSubscriber = nh->subscribe("/scan", 1, &depth_occupancy_map::scan_callback, this);
std::string scan_topic;
nh.param<std::string>("/homer_scan_topic", scan_topic, "/scan");
m_ScanSubscriber = nh->subscribe(scan_topic, 1, &depth_occupancy_map::scan_callback, this);
m_StartNavigationSubscriber = nh->subscribe("/homer_navigation/start_navigation", 3,
&depth_occupancy_map::startNavigationCallback, this);
m_MoveBaseSimpleGoalSubscriber = nh->subscribe(
......
......@@ -13,8 +13,10 @@ HomerNavigationNode::HomerNavigationNode()
nh.param<std::string>("/homer_scan_topic", scan_topic, "/scan");
m_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>(
scan_topic, 3, &HomerNavigationNode::laserDataCallback, this);
std::string front_scan_topic;
nh.param<std::string>("/homer_front_scan_topic", front_scan_topic, "/front_scan");
m_down_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>(
"/front_scan", 3, &HomerNavigationNode::laserDataCallback, this);
front_scan_topic, 3, &HomerNavigationNode::laserDataCallback, this);
m_start_navigation_sub
= nh.subscribe<homer_mapnav_msgs::StartNavigation>("/homer_navigation/start_navigation", 3,
&HomerNavigationNode::startNavigationCallback, this);
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment