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 #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 const std::string JOINT_TRAJECTORY_ACTION_PARAM_NAME = "joint_trajectory_action/joints";
00042
00043 class JointTrajectoryExecuter
00044 {
00045 private:
00046 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JTAS;
00047 typedef JTAS::GoalHandle GoalHandle;
00048 public:
00049 JointTrajectoryExecuter(ros::NodeHandle &n) :
00050 node_(n),
00051 action_server_(node_, "joint_trajectory_action",
00052 boost::bind(&JointTrajectoryExecuter::goalCB, this, _1),
00053 boost::bind(&JointTrajectoryExecuter::cancelCB, this, _1),
00054 false),
00055 has_active_goal_(false)
00056 {
00057 using namespace XmlRpc;
00058 ros::NodeHandle pn("~");
00059
00060 fetchParameters(ros::this_node::getNamespace());
00061
00062
00063 pub_controller_command_ =
00064 node_.advertise<trajectory_msgs::JointTrajectory>("command", 1);
00065 sub_controller_state_ =
00066 node_.subscribe("feedback_states", 1, &JointTrajectoryExecuter::controllerStateCB, this);
00067
00068 action_server_.start();
00069 }
00070
00071 void fetchParameters(std::string nameSpace="")
00072 {
00073 XmlRpc::XmlRpcValue jointNames;
00074 ros::NodeHandle nh;
00075
00076 if(nh.getParam(nameSpace + "/" + JOINT_TRAJECTORY_ACTION_PARAM_NAME,jointNames))
00077 {
00078 if(jointNames.size() == 0)
00079 {
00080 ROS_ERROR_STREAM(ros::this_node::getName()<<
00081 ": Found 0 joints under parameter "<<JOINT_TRAJECTORY_ACTION_PARAM_NAME);
00082 ros::shutdown();
00083 }
00084 }
00085 else
00086 {
00087 ROS_ERROR_STREAM(ros::this_node::getName()<<
00088 ": Could not find joint definitions under parameter "<<JOINT_TRAJECTORY_ACTION_PARAM_NAME);
00089 ros::shutdown();
00090 }
00091
00092 joint_names_.clear();
00093 for(int i = 0; i < jointNames.size(); i++)
00094 {
00095 std::string name = static_cast<std::string>(jointNames[i]);
00096 joint_names_.push_back(name);
00097 }
00098
00099
00100 goal_constraints_.clear();
00101 for (size_t i = 0; i < joint_names_.size(); ++i)
00102 {
00103 std::string ns = std::string("constraints/") + joint_names_[i];
00104 double g, t;
00105 nh.param(ns + "/goal", g, DEFAULT_GOAL_THRESHOLD);
00106 nh.param(ns + "/trajectory", t, -1.0);
00107 goal_constraints_[joint_names_[i]] = g;
00108 trajectory_constraints_[joint_names_[i]] = t;
00109 }
00110
00111 nh.param("constraints/stopped_velocity_tolerance", stopped_velocity_tolerance_, 0.01);
00112
00113 }
00114
00115 ~JointTrajectoryExecuter()
00116 {
00117 pub_controller_command_.shutdown();
00118 sub_controller_state_.shutdown();
00119 watchdog_timer_.stop();
00120 }
00121
00122 bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00123 const std::map<std::string, double>& constraints,
00124 const trajectory_msgs::JointTrajectory& traj) {
00125 ROS_DEBUG("Checking goal contraints");
00126 int last = traj.points.size() - 1;
00127 for (size_t i = 0; i < msg->joint_names.size(); ++i)
00128 {
00129 double abs_error = fabs(msg->actual.positions[i]-traj.points[last].positions[i]);
00130 double goal_constraint = constraints.at(msg->joint_names[i]);
00131 if (goal_constraint >= 0 && abs_error > goal_constraint)
00132 {
00133 ROS_DEBUG("Bad constraint: %f, abs_errs: %f", goal_constraint, abs_error);
00134 return false;
00135 }
00136 ROS_DEBUG("Checking constraint: %f, abs_errs: %f", goal_constraint, abs_error);
00137 }
00138 return true;
00139 }
00140
00141 private:
00142
00143 static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
00144 {
00145 if (a.size() != b.size())
00146 return false;
00147
00148 for (size_t i = 0; i < a.size(); ++i)
00149 {
00150 if (count(b.begin(), b.end(), a[i]) != 1)
00151 return false;
00152 }
00153 for (size_t i = 0; i < b.size(); ++i)
00154 {
00155 if (count(a.begin(), a.end(), b[i]) != 1)
00156 return false;
00157 }
00158
00159 return true;
00160 }
00161
00162 void watchdog(const ros::TimerEvent &e)
00163 {
00164 ros::Time now = ros::Time::now();
00165
00166
00167 if (has_active_goal_)
00168 {
00169 bool should_abort = false;
00170 if (!last_controller_state_)
00171 {
00172 should_abort = true;
00173 ROS_WARN("Aborting goal because we have never heard a controller state message.");
00174 }
00175 else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
00176 {
00177 should_abort = true;
00178 ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
00179 (now - last_controller_state_->header.stamp).toSec());
00180 }
00181
00182 if (should_abort)
00183 {
00184
00185 trajectory_msgs::JointTrajectory empty;
00186 empty.joint_names = joint_names_;
00187 pub_controller_command_.publish(empty);
00188
00189
00190 active_goal_.setAborted();
00191 has_active_goal_ = false;
00192 }
00193 }
00194 }
00195
00196 void goalCB(GoalHandle gh)
00197 {
00198
00199 ROS_DEBUG("Received goal: goalCB");
00200 if (!setsEqual(joint_names_, gh.getGoal()->trajectory.joint_names))
00201 {
00202 ROS_ERROR("Joints on incoming goal don't match our joints");
00203 gh.setRejected();
00204 return;
00205 }
00206
00207
00208 if (has_active_goal_)
00209 {
00210 ROS_DEBUG("Received new goal, canceling current goal");
00211
00212 trajectory_msgs::JointTrajectory empty;
00213 empty.joint_names = joint_names_;
00214 pub_controller_command_.publish(empty);
00215
00216
00217 active_goal_.setCanceled();
00218 has_active_goal_ = false;
00219 }
00220
00221
00222 if(withinGoalConstraints(last_controller_state_,
00223 goal_constraints_,
00224 gh.getGoal()->trajectory)) {
00225 ROS_INFO_STREAM("Already within goal constraints");
00226 gh.setAccepted();
00227 gh.setSucceeded();
00228 } else {
00229 gh.setAccepted();
00230 active_goal_ = gh;
00231 has_active_goal_ = true;
00232
00233 ROS_INFO("Publishing trajectory");
00234
00235 current_traj_ = active_goal_.getGoal()->trajectory;
00236 pub_controller_command_.publish(current_traj_);
00237 }
00238 }
00239
00240 void cancelCB(GoalHandle gh)
00241 {
00242 ROS_DEBUG("Received action cancel request");
00243 if (active_goal_ == gh)
00244 {
00245
00246 trajectory_msgs::JointTrajectory empty;
00247 empty.joint_names = joint_names_;
00248 pub_controller_command_.publish(empty);
00249
00250
00251 active_goal_.setCanceled();
00252 has_active_goal_ = false;
00253 }
00254 }
00255
00256
00257 ros::NodeHandle node_;
00258 JTAS action_server_;
00259 ros::Publisher pub_controller_command_;
00260 ros::Subscriber sub_controller_state_;
00261 ros::Timer watchdog_timer_;
00262
00263 bool has_active_goal_;
00264 GoalHandle active_goal_;
00265 trajectory_msgs::JointTrajectory current_traj_;
00266
00267
00268 std::vector<std::string> joint_names_;
00269 std::map<std::string,double> goal_constraints_;
00270 std::map<std::string,double> trajectory_constraints_;
00271 double goal_time_constraint_;
00272 double stopped_velocity_tolerance_;
00273
00274 control_msgs::FollowJointTrajectoryFeedbackConstPtr last_controller_state_;
00275
00276 void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
00277 {
00278
00279 last_controller_state_ = msg;
00280 ros::Time now = ros::Time::now();
00281
00282 if (!has_active_goal_)
00283 {
00284
00285 return;
00286 }
00287 if (current_traj_.points.empty())
00288 {
00289 ROS_DEBUG("Current trajecotry is empty, ignoring feedback");
00290 return;
00291 }
00292
00293
00294
00295
00296
00297 if (!setsEqual(joint_names_, msg->joint_names))
00298 {
00299 ROS_ERROR("Joint names from the controller don't match our joint names.");
00300 return;
00301 }
00302
00303
00304
00305
00306 ROS_DEBUG("Checking goal contraints");
00307 if(withinGoalConstraints(msg,
00308 goal_constraints_,
00309 current_traj_)) {
00310 ROS_INFO("Inside goal contraints, return success for action");
00311 active_goal_.setSucceeded();
00312 has_active_goal_ = false;
00313 }
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378 }
00379 };
00380
00381
00382 int main(int argc, char** argv)
00383 {
00384 ros::init(argc, argv, "joint_trajectory_action_node");
00385 ros::NodeHandle node;
00386 JointTrajectoryExecuter jte(node);
00387
00388 ros::spin();
00389
00390 return 0;
00391 }
00392
00393
00394
00395