Action server for high-level movement commands. More...
#include <rail_lab_location_server.hpp>
Public Member Functions | |
rail_lab_location_server () | |
Creates a rail_lab_location_server. | |
Private Member Functions | |
void | active () |
void | done (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
void | execute (const carl_navigation::MoveCarlGoalConstPtr &goal) |
void | feedback (const move_base_msgs::MoveBaseFeedbackConstPtr &feedback) |
Private Attributes | |
actionlib::SimpleActionServer < carl_navigation::MoveCarlAction > | as_ |
carl_navigation::MoveCarlFeedback | feedback_ |
std::vector< location > | locations_ |
actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > | move_base_ |
ros::NodeHandle | node_ |
carl_navigation::MoveCarlResult | result_ |
Action server for high-level movement commands.
The rail_lab_location_server handles the creation of the ROS action servers.
Definition at line 30 of file rail_lab_location_server.hpp.
Creates a rail_lab_location_server.
Creates a rail_lab_location_server object that creates the necessary action servers for high level navigation.
Definition at line 19 of file rail_lab_location_server.cpp.
void rail_lab_location_server::active | ( | ) | [private] |
The activation callback from move_base.
Definition at line 164 of file rail_lab_location_server.cpp.
void rail_lab_location_server::done | ( | const actionlib::SimpleClientGoalState & | state, |
const move_base_msgs::MoveBaseResultConstPtr & | result | ||
) | [private] |
The move_base finished callback.
state | The final state. |
result | The result from move_base. |
Definition at line 144 of file rail_lab_location_server.cpp.
void rail_lab_location_server::execute | ( | const carl_navigation::MoveCarlGoalConstPtr & | goal | ) | [private] |
The main action server execution method. A call to move_base will be made from here.
goal | The current goal. |
Definition at line 96 of file rail_lab_location_server.cpp.
void rail_lab_location_server::feedback | ( | const move_base_msgs::MoveBaseFeedbackConstPtr & | feedback | ) | [private] |
The feedback callback from move_base.
feedback | The feedback from move_base. |
Definition at line 169 of file rail_lab_location_server.cpp.
actionlib::SimpleActionServer<carl_navigation::MoveCarlAction> rail_lab_location_server::as_ [private] |
main action server
Definition at line 70 of file rail_lab_location_server.hpp.
carl_navigation::MoveCarlFeedback rail_lab_location_server::feedback_ [private] |
shared feedback
Definition at line 72 of file rail_lab_location_server.hpp.
std::vector<location> rail_lab_location_server::locations_ [private] |
pre-defined locations
Definition at line 73 of file rail_lab_location_server.hpp.
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> rail_lab_location_server::move_base_ [private] |
move_base action client
Definition at line 69 of file rail_lab_location_server.hpp.
a handle for this ROS node
Definition at line 68 of file rail_lab_location_server.hpp.
carl_navigation::MoveCarlResult rail_lab_location_server::result_ [private] |
shared result
Definition at line 71 of file rail_lab_location_server.hpp.