diff --git a/homer_navigation/include/homer_navigation/homer_navigation_node.h b/homer_navigation/include/homer_navigation/homer_navigation_node.h
index fadef9bb885da0d6e08fcf6a865f7ab03f402242..5765fae5f6d3415c4b29078493c363d9e63b698c 100644
--- a/homer_navigation/include/homer_navigation/homer_navigation_node.h
+++ b/homer_navigation/include/homer_navigation/homer_navigation_node.h
@@ -66,7 +66,6 @@ class HomerNavigationNode {
     void ignoreLaserCallback(const std_msgs::String::ConstPtr& msg);
     void poseCallback(const geometry_msgs::PoseStamped::ConstPtr& msg);
     void laserDataCallback(const sensor_msgs::LaserScan::ConstPtr& msg);
-    void downlaserDataCallback(const sensor_msgs::LaserScan::ConstPtr& msg);
     void startNavigationCallback(
         const homer_mapnav_msgs::StartNavigation::ConstPtr& msg);
     void moveBaseSimpleGoalCallback(
@@ -85,7 +84,6 @@ class HomerNavigationNode {
     virtual void init();
 
     void initNewTarget();
-    void processLaserScan(const sensor_msgs::LaserScan::ConstPtr& msg);
 
    private:
     /** @brief Start navigation to m_Target on  last_map_data_ */
diff --git a/homer_navigation/src/homer_navigation_node.cpp b/homer_navigation/src/homer_navigation_node.cpp
index 82dc933c1604734e253a431f34ee60391337f50f..d7d0aeadbdd7b316fdbaa65d686a30793166a575 100644
--- a/homer_navigation/src/homer_navigation_node.cpp
+++ b/homer_navigation/src/homer_navigation_node.cpp
@@ -11,7 +11,7 @@ HomerNavigationNode::HomerNavigationNode() {
     m_laser_data_sub = nh.subscribe<sensor_msgs::LaserScan>(
         "/scan", 1, &HomerNavigationNode::laserDataCallback, this);
     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>(
         "/homer_navigation/start_navigation", 1,
         &HomerNavigationNode::startNavigationCallback, this);
@@ -1087,7 +1087,7 @@ void HomerNavigationNode::maxDepthMoveDistanceCallback(
     calcMaxMoveDist();
 }
 
-void HomerNavigationNode::processLaserScan(
+void HomerNavigationNode::laserDataCallback(
     const sensor_msgs::LaserScan::ConstPtr& msg) {
     m_scan_map[msg->header.frame_id] = msg;
     m_last_laser_time = ros::Time::now();
@@ -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() {
     m_initial_path_reaches_target = false;
     m_avoided_collision = false;