00001 00011 #ifndef RAIL_LAB_LOCATION_SERVER_HPP_ 00012 #define RAIL_LAB_LOCATION_SERVER_HPP_ 00013 00014 #include <ros/ros.h> 00015 #include <actionlib/client/simple_action_client.h> 00016 #include <actionlib/server/simple_action_server.h> 00017 #include <move_base_msgs/MoveBaseAction.h> 00018 #include <carl_navigation/location.hpp> 00019 #include <carl_navigation/MoveCarlAction.h> 00020 #include <carl_navigation/MoveCarlActionGoal.h> 00021 #include <carl_navigation/MoveCarlActionResult.h> 00022 #include <vector> 00023 00030 class rail_lab_location_server 00031 { 00032 public: 00038 rail_lab_location_server(); 00039 00040 private: 00046 void execute(const carl_navigation::MoveCarlGoalConstPtr &goal); 00047 00054 void done(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr &result); 00055 00059 void active(); 00060 00066 void feedback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback); 00067 00068 ros::NodeHandle node_; 00069 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> move_base_; 00070 actionlib::SimpleActionServer<carl_navigation::MoveCarlAction> as_; 00071 carl_navigation::MoveCarlResult result_; 00072 carl_navigation::MoveCarlFeedback feedback_; 00073 std::vector<location> locations_; 00074 }; 00075 00083 int main(int argc, char **argv); 00084 00085 #endif