$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 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/limited_proxy.h> 00049 #include <control_toolbox/pid.h> 00050 #include <filters/filter_chain.h> 00051 #include <pr2_controller_interface/controller.h> 00052 #include <realtime_tools/realtime_publisher.h> 00053 #include <realtime_tools/realtime_box.h> 00054 00055 00056 #include <control_msgs/FollowJointTrajectoryAction.h> 00057 #include <trajectory_msgs/JointTrajectory.h> 00058 #include <pr2_controllers_msgs/QueryTrajectoryState.h> 00059 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h> 00060 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 00061 00062 00063 namespace controller { 00064 00065 template <class Action> 00066 class RTServerGoalHandle 00067 { 00068 private: 00069 ACTION_DEFINITION(Action); 00070 00071 //typedef actionlib::ActionServer<Action>::GoalHandle GoalHandle; 00072 typedef actionlib::ServerGoalHandle<Action> GoalHandle; 00073 typedef boost::shared_ptr<Result> ResultPtr; 00074 00075 uint8_t state_; 00076 00077 bool req_abort_; 00078 bool req_succeed_; 00079 ResultConstPtr req_result_; 00080 00081 public: 00082 GoalHandle gh_; 00083 ResultPtr preallocated_result_; // Preallocated so it can be used in realtime 00084 00085 RTServerGoalHandle(GoalHandle &gh, const ResultPtr &preallocated_result = ResultPtr((Result*)NULL)) 00086 : req_abort_(false), req_succeed_(false), gh_(gh), preallocated_result_(preallocated_result) 00087 { 00088 if (!preallocated_result_) 00089 preallocated_result_.reset(new Result); 00090 } 00091 00092 void setAborted(ResultConstPtr result = ResultConstPtr((Result*)NULL)) 00093 { 00094 if (!req_succeed_ && !req_abort_) 00095 { 00096 req_result_ = result; 00097 req_abort_ = true; 00098 } 00099 } 00100 00101 void setSucceeded(ResultConstPtr result = ResultConstPtr((Result*)NULL)) 00102 { 00103 if (!req_succeed_ && !req_abort_) 00104 { 00105 req_result_ = result; 00106 req_succeed_ = true; 00107 } 00108 } 00109 00110 bool valid() 00111 { 00112 return gh_.getGoal() != NULL; 00113 } 00114 00115 void runNonRT(const ros::TimerEvent &te) 00116 { 00117 using namespace actionlib_msgs; 00118 if (valid()) 00119 { 00120 actionlib_msgs::GoalStatus gs = gh_.getGoalStatus(); 00121 if (req_abort_ && gs.status == GoalStatus::ACTIVE) 00122 { 00123 if (req_result_) 00124 gh_.setAborted(*req_result_); 00125 else 00126 gh_.setAborted(); 00127 } 00128 else if (req_succeed_ && gs.status == GoalStatus::ACTIVE) 00129 { 00130 if (req_result_) 00131 gh_.setSucceeded(*req_result_); 00132 else 00133 gh_.setSucceeded(); 00134 } 00135 } 00136 } 00137 }; 00138 00139 class JointTolerance 00140 { 00141 public: 00142 JointTolerance(double _position = 0, double _velocity = 0, double _acceleration = 0) : 00143 position(_position), velocity(_velocity), acceleration(_acceleration) 00144 { 00145 } 00146 00147 bool violated(double p_err, double v_err = 0, double a_err = 0) const 00148 { 00149 return 00150 (position > 0 && fabs(p_err) > position) || 00151 (velocity > 0 && fabs(v_err) > velocity) || 00152 (acceleration > 0 && fabs(a_err) > acceleration); 00153 } 00154 00155 double position; 00156 double velocity; 00157 double acceleration; 00158 }; 00159 00160 00161 class JointTrajectoryActionController : public pr2_controller_interface::Controller 00162 { 00163 // Action typedefs for the original PR2 specific joint trajectory action 00164 typedef actionlib::ActionServer<pr2_controllers_msgs::JointTrajectoryAction> JTAS; 00165 typedef JTAS::GoalHandle GoalHandle; 00166 typedef RTServerGoalHandle<pr2_controllers_msgs::JointTrajectoryAction> RTGoalHandle; 00167 00168 // Action typedefs for the new follow joint trajectory action 00169 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> FJTAS; 00170 typedef FJTAS::GoalHandle GoalHandleFollow; 00171 typedef RTServerGoalHandle<control_msgs::FollowJointTrajectoryAction> RTGoalHandleFollow; 00172 00173 public: 00174 00175 JointTrajectoryActionController(); 00176 ~JointTrajectoryActionController(); 00177 00178 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00179 00180 void starting(); 00181 void update(); 00182 00183 private: 00184 int loop_count_; 00185 pr2_mechanism_model::RobotState *robot_; 00186 ros::Time last_time_; 00187 std::vector<pr2_mechanism_model::JointState*> joints_; 00188 std::vector<double> masses_; // Rough estimate of joint mass, used for feedforward control 00189 std::vector<control_toolbox::Pid> pids_; 00190 std::vector<bool> proxies_enabled_; 00191 std::vector<control_toolbox::LimitedProxy> proxies_; 00192 00193 std::vector<JointTolerance> default_trajectory_tolerance_; 00194 std::vector<JointTolerance> default_goal_tolerance_; 00195 double default_goal_time_constraint_; 00196 00197 /* 00198 double goal_time_constraint_; 00199 double stopped_velocity_tolerance_; 00200 std::vector<double> goal_constraints_; 00201 std::vector<double> trajectory_constraints_; 00202 */ 00203 std::vector<boost::shared_ptr<filters::FilterChain<double> > > output_filters_; 00204 00205 ros::NodeHandle node_; 00206 00207 void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg); 00208 ros::Subscriber sub_command_; 00209 00210 bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, 00211 pr2_controllers_msgs::QueryTrajectoryState::Response &resp); 00212 ros::ServiceServer serve_query_state_; 00213 00214 boost::scoped_ptr< 00215 realtime_tools::RealtimePublisher< 00216 pr2_controllers_msgs::JointTrajectoryControllerState> > controller_state_publisher_; 00217 00218 boost::scoped_ptr<JTAS> action_server_; 00219 boost::scoped_ptr<FJTAS> action_server_follow_; 00220 void goalCB(GoalHandle gh); 00221 void cancelCB(GoalHandle gh); 00222 void goalCBFollow(GoalHandleFollow gh); 00223 void cancelCBFollow(GoalHandleFollow gh); 00224 ros::Timer goal_handle_timer_; 00225 00226 boost::shared_ptr<RTGoalHandle> rt_active_goal_; 00227 boost::shared_ptr<RTGoalHandleFollow> rt_active_goal_follow_; 00228 00229 // ------ Mechanisms for passing the trajectory into realtime 00230 00231 void commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &traj, 00232 boost::shared_ptr<RTGoalHandle> gh = boost::shared_ptr<RTGoalHandle>((RTGoalHandle*)NULL), 00233 boost::shared_ptr<RTGoalHandleFollow> gh_follow = boost::shared_ptr<RTGoalHandleFollow>((RTGoalHandleFollow*)NULL)); 00234 00235 void preemptActiveGoal(); 00236 00237 // coef[0] + coef[1]*t + ... + coef[5]*t^5 00238 struct Spline 00239 { 00240 std::vector<double> coef; 00241 00242 Spline() : coef(6, 0.0) {} 00243 }; 00244 00245 struct Segment 00246 { 00247 double start_time; 00248 double duration; 00249 std::vector<Spline> splines; 00250 00251 std::vector<JointTolerance> trajectory_tolerance; 00252 std::vector<JointTolerance> goal_tolerance; 00253 double goal_time_tolerance; 00254 00255 boost::shared_ptr<RTGoalHandle> gh; 00256 boost::shared_ptr<RTGoalHandleFollow> gh_follow; // Goal handle for the newer FollowJointTrajectory action 00257 }; 00258 typedef std::vector<Segment> SpecifiedTrajectory; 00259 00260 realtime_tools::RealtimeBox< 00261 boost::shared_ptr<const SpecifiedTrajectory> > current_trajectory_box_; 00262 00263 // Holds the trajectory that we are currently following. The mutex 00264 // guarding current_trajectory_ is locked from within realtime, so 00265 // it may only be locked for a bounded duration. 00266 //boost::shared_ptr<const SpecifiedTrajectory> current_trajectory_; 00267 //boost::recursive_mutex current_trajectory_lock_RT_; 00268 00269 std::vector<double> q, qd, qdd; // Preallocated in init 00270 00271 // Samples, but handling time bounds. When the time is past the end 00272 // of the spline duration, the position is the last valid position, 00273 // and the derivatives are all 0. 00274 static void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time, 00275 double& position, double& velocity, double& acceleration); 00276 }; 00277 00278 } 00279 00280 #endif