43 : navigate_action_server_(nh, name, false), goal_cb_(cb)
54 const geometry_msgs::Pose2D& pose = nav_state.global_pose.pose;
55 if (
feedback_.state.global_pose.header.frame_id.length() > 0)
58 const geometry_msgs::Pose2D& prev_pose =
feedback_.state.global_pose.pose;
64 if (
feedback_.state.global_plan.poses.size() > 0)
67 double total_distance =
feedback_.distance_traveled +
feedback_.estimated_distance_remaining;
68 if (total_distance != 0.0)
83 locomotor_msgs::NavigateToPoseResult result;
84 result.result_code = result_code;
92 feedback_.estimated_distance_remaining = 0.0;
93 feedback_.state = locomotor_msgs::NavigationState();
102 locomotor_msgs::NavigateToPoseResult result;
103 result.result_code.result_code = -1;
104 result.result_code.message =
"Preempted.";
boost::shared_ptr< const Goal > acceptNewGoal()
void failNavigation(const locomotor_msgs::ResultCode &result_code)
void publishFeedback(const FeedbackConstPtr &feedback)
LocomotorActionServer(const ros::NodeHandle nh, NewGoalCallback cb, const std::string name="navigate")
std::function< void(const nav_2d_msgs::Pose2DStamped &)> NewGoalCallback
void completeNavigation()
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void publishFeedback(const locomotor_msgs::NavigationState &nav_state)
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
void registerPreemptCallback(boost::function< void()> cb)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
double getPlanLength(const nav_2d_msgs::Path2D &plan, const unsigned int start_index=0)
actionlib::SimpleActionServer< locomotor_msgs::NavigateToPoseAction > navigate_action_server_
void registerGoalCallback(boost::function< void()> cb)
locomotor_msgs::NavigateToPoseFeedback feedback_