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
00037 #ifndef JOINT_TRAJECTORY_ACTION_CONTROLLER_H__
00038 #define JOINT_TRAJECTORY_ACTION_CONTROLLER_H__
00039
00040 #include <vector>
00041
00042 #include <boost/scoped_ptr.hpp>
00043 #include <boost/thread/recursive_mutex.hpp>
00044 #include <boost/thread/condition.hpp>
00045 #include <ros/node_handle.h>
00046
00047 #include <actionlib/server/action_server.h>
00048 #include <control_toolbox/pid.h>
00049 #include <filters/filter_chain.h>
00050 #include <pr2_controller_interface/controller.h>
00051 #include <realtime_tools/realtime_publisher.h>
00052 #include <realtime_tools/realtime_box.h>
00053
00054
00055 #include <control_msgs/FollowJointTrajectoryAction.h>
00056 #include <trajectory_msgs/JointTrajectory.h>
00057 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
00058 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
00059 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00060
00061
00062 namespace controller {
00063
00064 template <class Action>
00065 class RTServerGoalHandle
00066 {
00067 private:
00068 ACTION_DEFINITION(Action);
00069
00070
00071 typedef actionlib::ServerGoalHandle<Action> GoalHandle;
00072 typedef boost::shared_ptr<Result> ResultPtr;
00073
00074 uint8_t state_;
00075
00076 bool req_abort_;
00077 bool req_succeed_;
00078 ResultConstPtr req_result_;
00079
00080 public:
00081 GoalHandle gh_;
00082 ResultPtr preallocated_result_;
00083
00084 RTServerGoalHandle(GoalHandle &gh, const ResultPtr &preallocated_result = ResultPtr((Result*)NULL))
00085 : req_abort_(false), req_succeed_(false), gh_(gh), preallocated_result_(preallocated_result)
00086 {
00087 if (!preallocated_result_)
00088 preallocated_result_.reset(new Result);
00089 }
00090
00091 void setAborted(ResultConstPtr result = ResultConstPtr((Result*)NULL))
00092 {
00093 if (!req_succeed_ && !req_abort_)
00094 {
00095 req_result_ = result;
00096 req_abort_ = true;
00097 }
00098 }
00099
00100 void setSucceeded(ResultConstPtr result = ResultConstPtr((Result*)NULL))
00101 {
00102 if (!req_succeed_ && !req_abort_)
00103 {
00104 req_result_ = result;
00105 req_succeed_ = true;
00106 }
00107 }
00108
00109 bool valid()
00110 {
00111 return gh_.getGoal() != NULL;
00112 }
00113
00114 void runNonRT(const ros::TimerEvent &te)
00115 {
00116 using namespace actionlib_msgs;
00117 if (valid())
00118 {
00119 actionlib_msgs::GoalStatus gs = gh_.getGoalStatus();
00120 if (req_abort_ && gs.status == GoalStatus::ACTIVE)
00121 {
00122 if (req_result_)
00123 gh_.setAborted(*req_result_);
00124 else
00125 gh_.setAborted();
00126 }
00127 else if (req_succeed_ && gs.status == GoalStatus::ACTIVE)
00128 {
00129 if (req_result_)
00130 gh_.setSucceeded(*req_result_);
00131 else
00132 gh_.setSucceeded();
00133 }
00134 }
00135 }
00136 };
00137
00138 class JointTolerance
00139 {
00140 public:
00141 JointTolerance(double _position = 0, double _velocity = 0, double _acceleration = 0) :
00142 position(_position), velocity(_velocity), acceleration(_acceleration)
00143 {
00144 }
00145
00146 bool violated(double p_err, double v_err = 0, double a_err = 0) const
00147 {
00148 return
00149 (position > 0 && fabs(p_err) > position) ||
00150 (velocity > 0 && fabs(v_err) > velocity) ||
00151 (acceleration > 0 && fabs(a_err) > acceleration);
00152 }
00153
00154 double position;
00155 double velocity;
00156 double acceleration;
00157 };
00158
00159
00160 class JointTrajectoryActionController : public pr2_controller_interface::Controller
00161 {
00162
00163 typedef actionlib::ActionServer<pr2_controllers_msgs::JointTrajectoryAction> JTAS;
00164 typedef JTAS::GoalHandle GoalHandle;
00165 typedef RTServerGoalHandle<pr2_controllers_msgs::JointTrajectoryAction> RTGoalHandle;
00166
00167
00168 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> FJTAS;
00169 typedef FJTAS::GoalHandle GoalHandleFollow;
00170 typedef RTServerGoalHandle<control_msgs::FollowJointTrajectoryAction> RTGoalHandleFollow;
00171
00172 public:
00173
00174 JointTrajectoryActionController();
00175 ~JointTrajectoryActionController();
00176
00177 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00178
00179 void starting();
00180 void update();
00181
00182 private:
00183 int loop_count_;
00184 pr2_mechanism_model::RobotState *robot_;
00185 ros::Time last_time_;
00186 std::vector<pr2_mechanism_model::JointState*> joints_;
00187 std::vector<control_toolbox::Pid> pids_;
00188
00189 std::vector<JointTolerance> default_trajectory_tolerance_;
00190 std::vector<JointTolerance> default_goal_tolerance_;
00191 double default_goal_time_constraint_;
00192
00193
00194
00195
00196
00197
00198
00199 std::vector<boost::shared_ptr<filters::FilterChain<double> > > output_filters_;
00200
00201 ros::NodeHandle node_;
00202
00203 void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg);
00204 ros::Subscriber sub_command_;
00205
00206 bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req,
00207 pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
00208 ros::ServiceServer serve_query_state_;
00209
00210 boost::scoped_ptr<
00211 realtime_tools::RealtimePublisher<
00212 pr2_controllers_msgs::JointTrajectoryControllerState> > controller_state_publisher_;
00213
00214 boost::scoped_ptr<JTAS> action_server_;
00215 boost::scoped_ptr<FJTAS> action_server_follow_;
00216 void goalCB(GoalHandle gh);
00217 void cancelCB(GoalHandle gh);
00218 void goalCBFollow(GoalHandleFollow gh);
00219 void cancelCBFollow(GoalHandleFollow gh);
00220 ros::Timer goal_handle_timer_;
00221
00222 boost::shared_ptr<RTGoalHandle> rt_active_goal_;
00223 boost::shared_ptr<RTGoalHandleFollow> rt_active_goal_follow_;
00224
00225
00226
00227 void commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &traj,
00228 boost::shared_ptr<RTGoalHandle> gh = boost::shared_ptr<RTGoalHandle>((RTGoalHandle*)NULL),
00229 boost::shared_ptr<RTGoalHandleFollow> gh_follow = boost::shared_ptr<RTGoalHandleFollow>((RTGoalHandleFollow*)NULL));
00230
00231 void preemptActiveGoal();
00232
00233
00234 struct Spline
00235 {
00236 std::vector<double> coef;
00237
00238 Spline() : coef(6, 0.0) {}
00239 };
00240
00241 struct Segment
00242 {
00243 double start_time;
00244 double duration;
00245 std::vector<Spline> splines;
00246
00247 std::vector<JointTolerance> trajectory_tolerance;
00248 std::vector<JointTolerance> goal_tolerance;
00249 double goal_time_tolerance;
00250
00251 boost::shared_ptr<RTGoalHandle> gh;
00252 boost::shared_ptr<RTGoalHandleFollow> gh_follow;
00253 };
00254 typedef std::vector<Segment> SpecifiedTrajectory;
00255
00256 realtime_tools::RealtimeBox<
00257 boost::shared_ptr<const SpecifiedTrajectory> > current_trajectory_box_;
00258
00259
00260
00261
00262
00263
00264
00265 std::vector<double> q, qd, qdd;
00266
00267
00268
00269
00270 static void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time,
00271 double& position, double& velocity, double& acceleration);
00272 };
00273
00274 }
00275
00276 #endif