joint_trajectory_action_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
37 #ifndef JOINT_TRAJECTORY_ACTION_CONTROLLER_H__
38 #define JOINT_TRAJECTORY_ACTION_CONTROLLER_H__
39 
40 #include <vector>
41 
42 #include <boost/scoped_ptr.hpp>
43 #include <boost/shared_ptr.hpp>
44 #include <ros/node_handle.h>
45 
48 #include <control_toolbox/pid.h>
49 #include <filters/filter_chain.hpp>
53 
54 
55 #include <control_msgs/FollowJointTrajectoryAction.h>
56 #include <trajectory_msgs/JointTrajectory.h>
57 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
58 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
59 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
60 
61 
62 namespace controller {
63 
64 template <class Action>
66 {
67 private:
68  ACTION_DEFINITION(Action);
69 
70  //typedef actionlib::ActionServer<Action>::GoalHandle GoalHandle;
72 #if ((actionlib_VERSION_MAJOR == 1) && (actionlib_VERSION_MINOR < 12)) || (actionlib_VERSION_MAJOR < 1)
75 #endif
76 
77  uint8_t state_;
78 
79  bool req_abort_;
81  ResultConstPtr req_result_;
82 
83 public:
84  GoalHandle gh_;
85  ResultPtr preallocated_result_; // Preallocated so it can be used in realtime
87 
88  RTServerGoalHandle(GoalHandle &gh, const ResultPtr &preallocated_result = ResultPtr((Result*)NULL))
89  : req_abort_(false), req_succeed_(false), gh_(gh), preallocated_result_(preallocated_result)
90  {
91  if (!preallocated_result_)
92  preallocated_result_.reset(new Result);
93  if (!preallocated_feedback_)
94  preallocated_feedback_.reset(new Feedback);
95  }
96 
97  void setAborted(ResultConstPtr result = ResultConstPtr((Result*)NULL))
98  {
99  if (!req_succeed_ && !req_abort_)
100  {
101  req_result_ = result;
102  req_abort_ = true;
103  }
104  }
105 
106  void setSucceeded(ResultConstPtr result = ResultConstPtr((Result*)NULL))
107  {
108  if (!req_succeed_ && !req_abort_)
109  {
110  req_result_ = result;
111  req_succeed_ = true;
112  }
113  }
114 
115  bool valid()
116  {
117  return gh_.getGoal() != NULL;
118  }
119 
120  void runNonRT(const ros::TimerEvent &te)
121  {
122  using namespace actionlib_msgs;
123  if (valid())
124  {
125  actionlib_msgs::GoalStatus gs = gh_.getGoalStatus();
126  if (req_abort_ && gs.status == GoalStatus::ACTIVE)
127  {
128  if (req_result_)
129  gh_.setAborted(*req_result_);
130  else
131  gh_.setAborted();
132  }
133  else if (req_succeed_ && gs.status == GoalStatus::ACTIVE)
134  {
135  if (req_result_)
136  gh_.setSucceeded(*req_result_);
137  else
138  gh_.setSucceeded();
139  }
140  }
141  }
142 };
143 
145 {
146 public:
147  JointTolerance(double _position = 0, double _velocity = 0, double _acceleration = 0) :
148  position(_position), velocity(_velocity), acceleration(_acceleration)
149  {
150  }
151 
152  bool violated(double p_err, double v_err = 0, double a_err = 0) const
153  {
154  return
155  (position > 0 && fabs(p_err) > position) ||
156  (velocity > 0 && fabs(v_err) > velocity) ||
157  (acceleration > 0 && fabs(a_err) > acceleration);
158  }
159 
160  double position;
161  double velocity;
162  double acceleration;
163 };
164 
165 
167 {
168  // Action typedefs for the original PR2 specific joint trajectory action
172 
173  // Action typedefs for the new follow joint trajectory action
177 
178 public:
179 
182 
184 
185  void starting();
186  void update();
187 
188 private:
192  std::vector<pr2_mechanism_model::JointState*> joints_;
193  std::vector<double> masses_; // Rough estimate of joint mass, used for feedforward control
194  std::vector<control_toolbox::Pid> pids_;
195  std::vector<bool> proxies_enabled_;
196  std::vector<control_toolbox::LimitedProxy> proxies_;
197 
198  std::vector<JointTolerance> default_trajectory_tolerance_;
199  std::vector<JointTolerance> default_goal_tolerance_;
201 
202  /*
203  double goal_time_constraint_;
204  double stopped_velocity_tolerance_;
205  std::vector<double> goal_constraints_;
206  std::vector<double> trajectory_constraints_;
207  */
208  std::vector<boost::shared_ptr<filters::FilterChain<double> > > output_filters_;
209 
211 
212  void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg);
214 
215  bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req,
216  pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
218 
219  boost::scoped_ptr<
221  pr2_controllers_msgs::JointTrajectoryControllerState> > controller_state_publisher_;
222 
223  boost::scoped_ptr<JTAS> action_server_;
224  boost::scoped_ptr<FJTAS> action_server_follow_;
225  void goalCB(GoalHandle gh);
226  void cancelCB(GoalHandle gh);
227  void goalCBFollow(GoalHandleFollow gh);
228  void cancelCBFollow(GoalHandleFollow gh);
230 
233 
234  // ------ Mechanisms for passing the trajectory into realtime
235 
236  void commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &traj,
239 
240  void preemptActiveGoal();
241 
242  // coef[0] + coef[1]*t + ... + coef[5]*t^5
243  struct Spline
244  {
245  std::vector<double> coef;
246 
247  Spline() : coef(6, 0.0) {}
248  };
249 
250  struct Segment
251  {
252  double start_time;
253  double duration;
254  std::vector<Spline> splines;
255 
256  std::vector<JointTolerance> trajectory_tolerance;
257  std::vector<JointTolerance> goal_tolerance;
259 
261  boost::shared_ptr<RTGoalHandleFollow> gh_follow; // Goal handle for the newer FollowJointTrajectory action
262  };
263  typedef std::vector<Segment> SpecifiedTrajectory;
264 
267 
268  // Holds the trajectory that we are currently following. The mutex
269  // guarding current_trajectory_ is locked from within realtime, so
270  // it may only be locked for a bounded duration.
271  //boost::shared_ptr<const SpecifiedTrajectory> current_trajectory_;
272  //boost::recursive_mutex current_trajectory_lock_RT_;
273 
274  std::vector<double> q, qd, qdd; // Preallocated in init
275 
276  // Samples, but handling time bounds. When the time is past the end
277  // of the spline duration, the position is the last valid position,
278  // and the derivatives are all 0.
279  static void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time,
280  double& position, double& velocity, double& acceleration);
281 };
282 
283 }
284 
285 #endif
actionlib::ServerGoalHandle< Action > GoalHandle
bool violated(double p_err, double v_err=0, double a_err=0) const
RTServerGoalHandle< pr2_controllers_msgs::JointTrajectoryAction > RTGoalHandle
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
boost::shared_ptr< const Goal > getGoal() const
RTServerGoalHandle(GoalHandle &gh, const ResultPtr &preallocated_result=ResultPtr((Result *) NULL))
void init(const M_string &remappings)
void setAborted(ResultConstPtr result=ResultConstPtr((Result *) NULL))
JointTolerance(double _position=0, double _velocity=0, double _acceleration=0)
actionlib_msgs::GoalStatus getGoalStatus() const
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void setSucceeded(ResultConstPtr result=ResultConstPtr((Result *) NULL))
boost::shared_ptr< RTGoalHandleFollow > rt_active_goal_follow_
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > FJTAS
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
RTServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RTGoalHandleFollow
std::vector< control_toolbox::LimitedProxy > proxies_
std::vector< boost::shared_ptr< filters::FilterChain< double > > > output_filters_
std::vector< pr2_mechanism_model::JointState * > joints_


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Sat Nov 12 2022 03:16:28