#include <locomotor_action_server.h>
Public Member Functions | |
void | completeNavigation () |
void | failNavigation (const locomotor_msgs::ResultCode &result_code) |
LocomotorActionServer (const ros::NodeHandle nh, NewGoalCallback cb, const std::string name="navigate") | |
void | publishFeedback (const locomotor_msgs::NavigationState &nav_state) |
Protected Member Functions | |
void | preemptCallback () |
void | preGoalCallback () |
Protected Attributes | |
locomotor_msgs::NavigateToPoseFeedback | feedback_ |
NewGoalCallback | goal_cb_ |
actionlib::SimpleActionServer< locomotor_msgs::NavigateToPoseAction > | navigate_action_server_ |
Definition at line 47 of file locomotor_action_server.h.
locomotor::LocomotorActionServer::LocomotorActionServer | ( | const ros::NodeHandle | nh, |
NewGoalCallback | cb, | ||
const std::string | name = "navigate" |
||
) |
Definition at line 42 of file locomotor_action_server.cpp.
void locomotor::LocomotorActionServer::completeNavigation | ( | ) |
Definition at line 75 of file locomotor_action_server.cpp.
void locomotor::LocomotorActionServer::failNavigation | ( | const locomotor_msgs::ResultCode & | result_code | ) |
Definition at line 80 of file locomotor_action_server.cpp.
|
protected |
Definition at line 99 of file locomotor_action_server.cpp.
|
protected |
Definition at line 88 of file locomotor_action_server.cpp.
void locomotor::LocomotorActionServer::publishFeedback | ( | const locomotor_msgs::NavigationState & | nav_state | ) |
Definition at line 49 of file locomotor_action_server.cpp.
|
protected |
Definition at line 58 of file locomotor_action_server.h.
|
protected |
Definition at line 59 of file locomotor_action_server.h.
|
protected |
Definition at line 57 of file locomotor_action_server.h.