Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <locomotor/locomotor_action_server.h>
00036 #include <nav_2d_utils/path_ops.h>
00037 #include <string>
00038
00039 namespace locomotor
00040 {
00041
00042 LocomotorActionServer::LocomotorActionServer(const ros::NodeHandle nh, NewGoalCallback cb, const std::string name)
00043 : navigate_action_server_(nh, name, false), goal_cb_(cb)
00044 {
00045 navigate_action_server_.registerGoalCallback(std::bind(&LocomotorActionServer::preGoalCallback, this));
00046 navigate_action_server_.registerPreemptCallback(std::bind(&LocomotorActionServer::preemptCallback, this));
00047 navigate_action_server_.start();
00048 }
00049 void LocomotorActionServer::publishFeedback(const locomotor_msgs::NavigationState& nav_state)
00050 {
00051 if (!navigate_action_server_.isActive()) return;
00052
00053
00054 const geometry_msgs::Pose2D& pose = nav_state.global_pose.pose;
00055 if (feedback_.state.global_pose.header.frame_id.length() > 0)
00056 {
00057
00058 const geometry_msgs::Pose2D& prev_pose = feedback_.state.global_pose.pose;
00059 feedback_.distance_traveled += nav_2d_utils::poseDistance(prev_pose, pose);
00060 }
00061
00062 feedback_.state = nav_state;
00063
00064 if (feedback_.state.global_plan.poses.size() > 0)
00065 {
00066 feedback_.estimated_distance_remaining = nav_2d_utils::getPlanLength(feedback_.state.global_plan, pose);
00067 double total_distance = feedback_.distance_traveled + feedback_.estimated_distance_remaining;
00068 if (total_distance != 0.0)
00069 feedback_.percent_complete = feedback_.distance_traveled / total_distance;
00070 }
00071
00072 navigate_action_server_.publishFeedback(feedback_);
00073 }
00074
00075 void LocomotorActionServer::completeNavigation()
00076 {
00077 if (!navigate_action_server_.isActive()) return;
00078 navigate_action_server_.setSucceeded();
00079 }
00080 void LocomotorActionServer::failNavigation(const locomotor_msgs::ResultCode& result_code)
00081 {
00082 if (!navigate_action_server_.isActive()) return;
00083 locomotor_msgs::NavigateToPoseResult result;
00084 result.result_code = result_code;
00085 navigate_action_server_.setAborted(result, result_code.message);
00086 }
00087
00088 void LocomotorActionServer::preGoalCallback()
00089 {
00090 feedback_.distance_traveled = 0.0;
00091 feedback_.percent_complete = 0.0;
00092 feedback_.estimated_distance_remaining = 0.0;
00093 feedback_.state = locomotor_msgs::NavigationState();
00094
00095 auto full_goal = navigate_action_server_.acceptNewGoal();
00096 goal_cb_(full_goal->goal);
00097 }
00098
00099 void LocomotorActionServer::preemptCallback()
00100 {
00101 if (!navigate_action_server_.isActive()) return;
00102 locomotor_msgs::NavigateToPoseResult result;
00103 result.result_code.result_code = -1;
00104 result.result_code.message = "Preempted.";
00105 navigate_action_server_.setPreempted(result, result.result_code.message);
00106 }
00107
00108 }