diff --git a/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h b/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h index 37082b6d..7bcd15a0 100644 --- a/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h +++ b/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h @@ -271,13 +271,6 @@ typedef boost::shared_ptr("current_goal", 1); // init cmd_vel publisher for the robot velocity diff --git a/mbf_abstract_nav/src/move_base_action.cpp b/mbf_abstract_nav/src/move_base_action.cpp index 83ef5e1e..0bf7f642 100644 --- a/mbf_abstract_nav/src/move_base_action.cpp +++ b/mbf_abstract_nav/src/move_base_action.cpp @@ -158,6 +158,7 @@ void MoveBaseAction::start(GoalHandle &goal_handle) goal_handle.setAborted(move_base_result, move_base_result.message); return; } + goal_pose_ = goal.target_pose; // wait for server connections if (!action_client_get_path_.waitForServer(connection_timeout) || @@ -250,7 +251,6 @@ void MoveBaseAction::actionGetPathDone( action_state_ = FAILED; const mbf_msgs::GetPathResult &result = *(result_ptr.get()); - const mbf_msgs::MoveBaseGoal& goal = *(goal_handle_.getGoal().get()); mbf_msgs::MoveBaseResult move_base_result; switch (state.state_) { @@ -294,8 +294,8 @@ void MoveBaseAction::actionGetPathDone( // copy result from get_path action move_base_result.outcome = result.outcome; move_base_result.message = result.message; - move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal.target_pose)); - move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal.target_pose)); + move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); move_base_result.final_pose = robot_pose_; ROS_WARN_STREAM_NAMED("move_base", "Abort the execution of the planner: " << result.message); @@ -309,8 +309,8 @@ void MoveBaseAction::actionGetPathDone( // copy result from get_path action move_base_result.outcome = result.outcome; move_base_result.message = result.message; - move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal.target_pose)); - move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal.target_pose)); + move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); move_base_result.final_pose = robot_pose_; goal_handle_.setCanceled(move_base_result, state.getText()); break; @@ -364,7 +364,6 @@ void MoveBaseAction::actionExePathDone( ROS_DEBUG_STREAM_NAMED("move_base", "Action \"exe_path\" finished."); const mbf_msgs::ExePathResult& result = *(result_ptr.get()); - const mbf_msgs::MoveBaseGoal& goal = *(goal_handle_.getGoal().get()); mbf_msgs::MoveBaseResult move_base_result; // copy result from get_path action @@ -490,14 +489,13 @@ void MoveBaseAction::actionRecoveryDone( action_state_ = FAILED; // unless recovery succeeds or gets canceled... const mbf_msgs::RecoveryResult& result = *(result_ptr.get()); - const mbf_msgs::MoveBaseGoal& goal = *(goal_handle_.getGoal().get()); mbf_msgs::MoveBaseResult move_base_result; // copy result from get_path action move_base_result.outcome = result.outcome; move_base_result.message = result.message; - move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal.target_pose)); - move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal.target_pose)); + move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); move_base_result.final_pose = robot_pose_; switch (state.state_) diff --git a/mbf_abstract_nav/src/robot_information.cpp b/mbf_abstract_nav/src/robot_information.cpp index e49b7591..b35195df 100644 --- a/mbf_abstract_nav/src/robot_information.cpp +++ b/mbf_abstract_nav/src/robot_information.cpp @@ -52,7 +52,6 @@ RobotInformation::RobotInformation(TF &tf_listener, } - bool RobotInformation::getRobotPose(geometry_msgs::PoseStamped &robot_pose) const { bool tf_success = mbf_utility::getRobotPose(tf_listener_, robot_frame_, global_frame_,