35 #ifndef LOCOMOTOR_LOCOMOTOR_ACTION_SERVER_H 36 #define LOCOMOTOR_LOCOMOTOR_ACTION_SERVER_H 39 #include <locomotor_msgs/NavigateToPoseAction.h> 40 #include <locomotor_msgs/NavigationState.h> 53 void failNavigation(
const locomotor_msgs::ResultCode& result_code);
63 #endif // LOCOMOTOR_LOCOMOTOR_ACTION_SERVER_H void failNavigation(const locomotor_msgs::ResultCode &result_code)
LocomotorActionServer(const ros::NodeHandle nh, NewGoalCallback cb, const std::string name="navigate")
std::function< void(const nav_2d_msgs::Pose2DStamped &)> NewGoalCallback
void completeNavigation()
void publishFeedback(const locomotor_msgs::NavigationState &nav_state)
actionlib::SimpleActionServer< locomotor_msgs::NavigateToPoseAction > navigate_action_server_
locomotor_msgs::NavigateToPoseFeedback feedback_