$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Southwest Research Institute 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above copyright 00013 * notice, this list of conditions and the following disclaimer in the 00014 * documentation and/or other materials provided with the distribution. 00015 * * Neither the name of the Southwest Research Institute, nor the names 00016 * of its contributors may be used to endorse or promote products derived 00017 * from this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 */ 00031 00032 00033 #include <ros/ros.h> 00034 #include <actionlib/server/action_server.h> 00035 00036 #include <trajectory_msgs/JointTrajectory.h> 00037 #include <control_msgs/FollowJointTrajectoryAction.h> 00038 #include <control_msgs/FollowJointTrajectoryFeedback.h> 00039 00040 const double DEFAULT_GOAL_THRESHOLD = 0.01; 00041 00042 class JointTrajectoryExecuter 00043 { 00044 private: 00045 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JTAS; 00046 typedef JTAS::GoalHandle GoalHandle; 00047 public: 00048 JointTrajectoryExecuter(ros::NodeHandle &n) : 00049 node_(n), 00050 action_server_(node_, "joint_trajectory_action", 00051 boost::bind(&JointTrajectoryExecuter::goalCB, this, _1), 00052 boost::bind(&JointTrajectoryExecuter::cancelCB, this, _1), 00053 false), 00054 has_active_goal_(false) 00055 { 00056 using namespace XmlRpc; 00057 ros::NodeHandle pn("~"); 00058 00059 joint_names_.push_back("joint_s"); 00060 joint_names_.push_back("joint_l"); 00061 joint_names_.push_back("joint_e"); 00062 joint_names_.push_back("joint_u"); 00063 joint_names_.push_back("joint_r"); 00064 joint_names_.push_back("joint_b"); 00065 joint_names_.push_back("joint_t"); 00066 00067 pn.param("constraints/goal_time", goal_time_constraint_, 0.0); 00068 00069 // Gets the constraints for each joint. 00070 for (size_t i = 0; i < joint_names_.size(); ++i) 00071 { 00072 std::string ns = std::string("constraints/") + joint_names_[i]; 00073 double g, t; 00074 pn.param(ns + "/goal", g, DEFAULT_GOAL_THRESHOLD); 00075 pn.param(ns + "/trajectory", t, -1.0); 00076 goal_constraints_[joint_names_[i]] = g; 00077 trajectory_constraints_[joint_names_[i]] = t; 00078 } 00079 pn.param("constraints/stopped_velocity_tolerance", stopped_velocity_tolerance_, 0.01); 00080 00081 00082 pub_controller_command_ = 00083 node_.advertise<trajectory_msgs::JointTrajectory>("command", 1); 00084 sub_controller_state_ = 00085 node_.subscribe("feedback_states", 1, &JointTrajectoryExecuter::controllerStateCB, this); 00086 00087 action_server_.start(); 00088 } 00089 00090 ~JointTrajectoryExecuter() 00091 { 00092 pub_controller_command_.shutdown(); 00093 sub_controller_state_.shutdown(); 00094 watchdog_timer_.stop(); 00095 } 00096 00097 private: 00098 00099 static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b) 00100 { 00101 if (a.size() != b.size()) 00102 return false; 00103 00104 for (size_t i = 0; i < a.size(); ++i) 00105 { 00106 if (count(b.begin(), b.end(), a[i]) != 1) 00107 return false; 00108 } 00109 for (size_t i = 0; i < b.size(); ++i) 00110 { 00111 if (count(a.begin(), a.end(), b[i]) != 1) 00112 return false; 00113 } 00114 00115 return true; 00116 } 00117 00118 void watchdog(const ros::TimerEvent &e) 00119 { 00120 ros::Time now = ros::Time::now(); 00121 00122 // Aborts the active goal if the controller does not appear to be active. 00123 if (has_active_goal_) 00124 { 00125 bool should_abort = false; 00126 if (!last_controller_state_) 00127 { 00128 should_abort = true; 00129 ROS_WARN("Aborting goal because we have never heard a controller state message."); 00130 } 00131 else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0)) 00132 { 00133 should_abort = true; 00134 ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds", 00135 (now - last_controller_state_->header.stamp).toSec()); 00136 } 00137 00138 if (should_abort) 00139 { 00140 // Stops the controller. 00141 trajectory_msgs::JointTrajectory empty; 00142 empty.joint_names = joint_names_; 00143 pub_controller_command_.publish(empty); 00144 00145 // Marks the current goal as aborted. 00146 active_goal_.setAborted(); 00147 has_active_goal_ = false; 00148 } 00149 } 00150 } 00151 00152 void goalCB(GoalHandle gh) 00153 { 00154 // Ensures that the joints in the goal match the joints we are commanding. 00155 ROS_DEBUG("Received goal: goalCB"); 00156 if (!setsEqual(joint_names_, gh.getGoal()->trajectory.joint_names)) 00157 { 00158 ROS_ERROR("Joints on incoming goal don't match our joints"); 00159 gh.setRejected(); 00160 return; 00161 } 00162 00163 // Cancels the currently active goal. 00164 if (has_active_goal_) 00165 { 00166 ROS_DEBUG("Received new goal, canceling current goal"); 00167 // Stops the controller. 00168 trajectory_msgs::JointTrajectory empty; 00169 empty.joint_names = joint_names_; 00170 pub_controller_command_.publish(empty); 00171 00172 // Marks the current goal as canceled. 00173 active_goal_.setCanceled(); 00174 has_active_goal_ = false; 00175 } 00176 00177 gh.setAccepted(); 00178 active_goal_ = gh; 00179 has_active_goal_ = true; 00180 00181 // Sends the trajectory along to the controller 00182 ROS_DEBUG("Publishing trajectory"); 00183 current_traj_ = active_goal_.getGoal()->trajectory; 00184 pub_controller_command_.publish(current_traj_); 00185 } 00186 00187 void cancelCB(GoalHandle gh) 00188 { 00189 ROS_DEBUG("Received action cancel request"); 00190 if (active_goal_ == gh) 00191 { 00192 // Stops the controller. 00193 trajectory_msgs::JointTrajectory empty; 00194 empty.joint_names = joint_names_; 00195 pub_controller_command_.publish(empty); 00196 00197 // Marks the current goal as canceled. 00198 active_goal_.setCanceled(); 00199 has_active_goal_ = false; 00200 } 00201 } 00202 00203 00204 ros::NodeHandle node_; 00205 JTAS action_server_; 00206 ros::Publisher pub_controller_command_; 00207 ros::Subscriber sub_controller_state_; 00208 ros::Timer watchdog_timer_; 00209 00210 bool has_active_goal_; 00211 GoalHandle active_goal_; 00212 trajectory_msgs::JointTrajectory current_traj_; 00213 00214 00215 std::vector<std::string> joint_names_; 00216 std::map<std::string,double> goal_constraints_; 00217 std::map<std::string,double> trajectory_constraints_; 00218 double goal_time_constraint_; 00219 double stopped_velocity_tolerance_; 00220 00221 control_msgs::FollowJointTrajectoryFeedbackConstPtr last_controller_state_; 00222 00223 void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg) 00224 { 00225 //ROS_DEBUG("Checking controller state feedback"); 00226 last_controller_state_ = msg; 00227 ros::Time now = ros::Time::now(); 00228 00229 if (!has_active_goal_) 00230 { 00231 //ROS_DEBUG("No active goal, ignoring feedback"); 00232 return; 00233 } 00234 if (current_traj_.points.empty()) 00235 { 00236 ROS_DEBUG("Current trajecotry is empty, ignoring feedback"); 00237 return; 00238 } 00239 /* NOT CONCERNED ABOUT TRAJECTORY TIMING AT THIS POINT 00240 if (now < current_traj_.header.stamp + current_traj_.points[0].time_from_start) 00241 return; 00242 */ 00243 00244 if (!setsEqual(joint_names_, msg->joint_names)) 00245 { 00246 ROS_ERROR("Joint names from the controller don't match our joint names."); 00247 return; 00248 } 00249 00250 // Checking for goal constraints 00251 // Checks that we have ended inside the goal constraints 00252 00253 ROS_DEBUG("Checking goal contraints"); 00254 bool inside_goal_constraints = true; 00255 int last = current_traj_.points.size() - 1; 00256 for (size_t i = 0; i < msg->joint_names.size() && inside_goal_constraints; ++i) 00257 { 00258 double abs_error = fabs(msg->actual.positions[i]-current_traj_.points[last].positions[i]); 00259 double goal_constraint = goal_constraints_[msg->joint_names[i]]; 00260 if (goal_constraint >= 0 && abs_error > goal_constraint) 00261 { 00262 inside_goal_constraints = false; 00263 } 00264 ROS_DEBUG("Checking constraint: %f, abs_errs: %f", goal_constraint, abs_error); 00265 } 00266 00267 if (inside_goal_constraints) 00268 { 00269 ROS_INFO("Inside goal contraints, return success for action"); 00270 active_goal_.setSucceeded(); 00271 has_active_goal_ = false; 00272 } 00273 // Verifies that the controller has stayed within the trajectory constraints. 00274 /* DISABLING THIS MORE COMPLICATED GOAL CHECKING AND ERROR DETECTION 00275 00276 00277 int last = current_traj_.points.size() - 1; 00278 ros::Time end_time = current_traj_.header.stamp + current_traj_.points[last].time_from_start; 00279 if (now < end_time) 00280 { 00281 // Checks that the controller is inside the trajectory constraints. 00282 for (size_t i = 0; i < msg->joint_names.size(); ++i) 00283 { 00284 double abs_error = fabs(msg->error.positions[i]); 00285 double constraint = trajectory_constraints_[msg->joint_names[i]]; 00286 if (constraint >= 0 && abs_error > constraint) 00287 { 00288 // Stops the controller. 00289 trajectory_msgs::JointTrajectory empty; 00290 empty.joint_names = joint_names_; 00291 pub_controller_command_.publish(empty); 00292 00293 active_goal_.setAborted(); 00294 has_active_goal_ = false; 00295 ROS_WARN("Aborting because we would up outside the trajectory constraints"); 00296 return; 00297 } 00298 } 00299 } 00300 else 00301 { 00302 // Checks that we have ended inside the goal constraints 00303 bool inside_goal_constraints = true; 00304 for (size_t i = 0; i < msg->joint_names.size() && inside_goal_constraints; ++i) 00305 { 00306 double abs_error = fabs(msg->error.positions[i]); 00307 double goal_constraint = goal_constraints_[msg->joint_names[i]]; 00308 if (goal_constraint >= 0 && abs_error > goal_constraint) 00309 inside_goal_constraints = false; 00310 00311 // It's important to be stopped if that's desired. 00312 if (fabs(msg->desired.velocities[i]) < 1e-6) 00313 { 00314 if (fabs(msg->actual.velocities[i]) > stopped_velocity_tolerance_) 00315 inside_goal_constraints = false; 00316 } 00317 } 00318 00319 if (inside_goal_constraints) 00320 { 00321 active_goal_.setSucceeded(); 00322 has_active_goal_ = false; 00323 } 00324 else if (now < end_time + ros::Duration(goal_time_constraint_)) 00325 { 00326 // Still have some time left to make it. 00327 } 00328 else 00329 { 00330 ROS_WARN("Aborting because we wound up outside the goal constraints"); 00331 active_goal_.setAborted(); 00332 has_active_goal_ = false; 00333 } 00334 00335 } 00336 */ 00337 } 00338 }; 00339 00340 00341 int main(int argc, char** argv) 00342 { 00343 ros::init(argc, argv, "joint_trajectory_action_node"); 00344 ros::NodeHandle node;//("~"); 00345 JointTrajectoryExecuter jte(node); 00346 00347 ros::spin(); 00348 00349 return 0; 00350 } 00351 00352 00353 00354