Skip to content
Snippets Groups Projects
Commit 741c2a3d authored by Florian Polster's avatar Florian Polster
Browse files

no seperate laserCallback

parent 0b30e442
No related branches found
No related tags found
No related merge requests found
...@@ -66,7 +66,6 @@ class HomerNavigationNode { ...@@ -66,7 +66,6 @@ class HomerNavigationNode {
void ignoreLaserCallback(const std_msgs::String::ConstPtr& msg); void ignoreLaserCallback(const std_msgs::String::ConstPtr& msg);
void poseCallback(const geometry_msgs::PoseStamped::ConstPtr& msg); void poseCallback(const geometry_msgs::PoseStamped::ConstPtr& msg);
void laserDataCallback(const sensor_msgs::LaserScan::ConstPtr& msg); void laserDataCallback(const sensor_msgs::LaserScan::ConstPtr& msg);
void downlaserDataCallback(const sensor_msgs::LaserScan::ConstPtr& msg);
void startNavigationCallback( void startNavigationCallback(
const homer_mapnav_msgs::StartNavigation::ConstPtr& msg); const homer_mapnav_msgs::StartNavigation::ConstPtr& msg);
void moveBaseSimpleGoalCallback( void moveBaseSimpleGoalCallback(
...@@ -85,7 +84,6 @@ class HomerNavigationNode { ...@@ -85,7 +84,6 @@ class HomerNavigationNode {
virtual void init(); virtual void init();
void initNewTarget(); void initNewTarget();
void processLaserScan(const sensor_msgs::LaserScan::ConstPtr& msg);
private: private:
/** @brief Start navigation to m_Target on last_map_data_ */ /** @brief Start navigation to m_Target on last_map_data_ */
......
...@@ -11,7 +11,7 @@ HomerNavigationNode::HomerNavigationNode() { ...@@ -11,7 +11,7 @@ HomerNavigationNode::HomerNavigationNode() {
m_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>( m_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>(
"/scan", 1, &HomerNavigationNode::laserDataCallback, this); "/scan", 1, &HomerNavigationNode::laserDataCallback, this);
m_down_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>( m_down_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>(
"/front_scan", 1, &HomerNavigationNode::downlaserDataCallback, this); "/front_scan", 1, &HomerNavigationNode::laserDataCallback, this);
m_start_navigation_sub = nh.subscribe<homer_mapnav_msgs::StartNavigation>( m_start_navigation_sub = nh.subscribe<homer_mapnav_msgs::StartNavigation>(
"/homer_navigation/start_navigation", 1, "/homer_navigation/start_navigation", 1,
&HomerNavigationNode::startNavigationCallback, this); &HomerNavigationNode::startNavigationCallback, this);
...@@ -1087,7 +1087,7 @@ void HomerNavigationNode::maxDepthMoveDistanceCallback( ...@@ -1087,7 +1087,7 @@ void HomerNavigationNode::maxDepthMoveDistanceCallback(
calcMaxMoveDist(); calcMaxMoveDist();
} }
void HomerNavigationNode::processLaserScan( void HomerNavigationNode::laserDataCallback(
const sensor_msgs::LaserScan::ConstPtr& msg) { const sensor_msgs::LaserScan::ConstPtr& msg) {
m_scan_map[msg->header.frame_id] = msg; m_scan_map[msg->header.frame_id] = msg;
m_last_laser_time = ros::Time::now(); m_last_laser_time = ros::Time::now();
...@@ -1105,16 +1105,6 @@ void HomerNavigationNode::processLaserScan( ...@@ -1105,16 +1105,6 @@ void HomerNavigationNode::processLaserScan(
} }
} }
void HomerNavigationNode::laserDataCallback(
const sensor_msgs::LaserScan::ConstPtr& msg) {
processLaserScan(msg);
}
void HomerNavigationNode::downlaserDataCallback(
const sensor_msgs::LaserScan::ConstPtr& msg) {
processLaserScan(msg);
}
void HomerNavigationNode::initNewTarget() { void HomerNavigationNode::initNewTarget() {
m_initial_path_reaches_target = false; m_initial_path_reaches_target = false;
m_avoided_collision = false; m_avoided_collision = false;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment