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
00036
00037
00038
00039
00040
00041
00042
00043 #ifndef PRIMITIVECALLBASE_HPP_
00044 #define PRIMITIVECALLBASE_HPP_
00045
00046 #include <ros/ros.h>
00047 #include <actionlib/client/simple_action_client.h>
00048
00049 #include <std_msgs/String.h>
00050
00051 namespace labust
00052 {
00053 namespace primitive
00054 {
00058 template <class ActionType, class ActionGoal, class ActionResult, class ActionFeedback>
00059 class PrimitiveCallBase
00060 {
00061 public:
00062
00063 typedef ActionType Action;
00064 typedef actionlib::SimpleActionClient<Action> ActionClient;
00065 typedef ActionGoal Goal;
00066 typedef ActionResult Result;
00067 typedef ActionFeedback Feedback;
00068
00069 protected:
00070
00074 PrimitiveCallBase(const std::string& name):primitiveName(name),
00075 ac(primitiveName.c_str())
00076 {
00077 ros::NodeHandle nh;
00078
00079
00080 pubEventString = nh.advertise<std_msgs::String>("eventString",1);
00081
00082
00083 ROS_INFO("Waiting for action server to start.");
00084 ac.waitForServer();
00085 ROS_INFO("Action server started, sending goal.");
00086 }
00087
00088 virtual ~PrimitiveCallBase(){}
00089
00090 public:
00091 virtual void start(Goal goal)
00092 {
00093
00094 this->callPrimitiveAction(goal);
00095 }
00096
00097 virtual void stop()
00098 {
00099
00100 ros::Duration(0.2).sleep();
00101 ac.cancelGoalsAtAndBeforeTime(ros::Time::now());
00102
00103
00104
00105
00106 }
00107
00108 protected:
00109 void callPrimitiveAction(Goal goal)
00110 {
00111 ac.sendGoal(goal,
00112 boost::bind(&PrimitiveCallBase::doneCb, this, _1, _2),
00113 boost::bind(&PrimitiveCallBase::activeCb, this),
00114 boost::bind(&PrimitiveCallBase::feedbackCb, this, _1));
00115 }
00116
00117
00118
00119 virtual void doneCb(const actionlib::SimpleClientGoalState& state, const typename Result::ConstPtr& result)
00120 {
00121 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00122 {
00123 ROS_ERROR("Finished in state [%s]", state.toString().c_str());
00124 publishEventString("/PRIMITIVE_FINISHED");
00125 }
00126 }
00127
00128
00129 virtual void activeCb()
00130 {
00131 ROS_ERROR("Goal just went active.");
00132 }
00133
00134
00135 virtual void feedbackCb(const typename Feedback::ConstPtr& feedback)
00136 {
00137
00138 }
00139
00140 void publishEventString(std::string event)
00141 {
00142 std_msgs::String msg;
00143 msg.data = event.c_str();
00144 pubEventString.publish(msg);
00145 }
00146
00150 std::string primitiveName;
00154 ActionClient ac;
00158 Action action;
00162 ros::ServiceClient control_manager;
00166 ros::Publisher pubEventString;
00167 };
00168 }
00169 }
00170
00171
00172
00173 #endif