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 #include <industrial_robot_client/joint_trajectory_action.h>
00033 #include <industrial_robot_client/utils.h>
00034 #include <industrial_utils/param_utils.h>
00035 #include <industrial_utils/utils.h>
00036
00037 namespace industrial_robot_client
00038 {
00039 namespace joint_trajectory_action
00040 {
00041
00042 const double JointTrajectoryAction::WATCHD0G_PERIOD_ = 1.0;
00043 const double JointTrajectoryAction::DEFAULT_GOAL_THRESHOLD_ = 0.01;
00044
00045 JointTrajectoryAction::JointTrajectoryAction() :
00046 action_server_(node_, "joint_trajectory_action", boost::bind(&JointTrajectoryAction::goalCB, this, _1),
00047 boost::bind(&JointTrajectoryAction::cancelCB, this, _1), false), has_active_goal_(false)
00048 {
00049 ros::NodeHandle pn("~");
00050
00051 pn.param("constraints/goal_threshold", goal_threshold_, DEFAULT_GOAL_THRESHOLD_);
00052
00053 if (!industrial_utils::param::getJointNames("controller_joint_names", "robot_description", joint_names_))
00054 ROS_ERROR("Failed to initialize joint_names.");
00055
00056
00057
00058 std::remove(joint_names_.begin(), joint_names_.end(), std::string());
00059 ROS_INFO_STREAM("Filtered joint names to " << joint_names_.size() << " joints");
00060
00061 pub_trajectory_command_ = node_.advertise<trajectory_msgs::JointTrajectory>("joint_path_command", 1);
00062 sub_trajectory_state_ = node_.subscribe("feedback_states", 1, &JointTrajectoryAction::controllerStateCB, this);
00063 sub_robot_status_ = node_.subscribe("robot_status", 1, &JointTrajectoryAction::robotStatusCB, this);
00064
00065 watchdog_timer_ = node_.createTimer(ros::Duration(WATCHD0G_PERIOD_), &JointTrajectoryAction::watchdog, this);
00066 action_server_.start();
00067 }
00068
00069 JointTrajectoryAction::~JointTrajectoryAction()
00070 {
00071 }
00072
00073 void JointTrajectoryAction::robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg)
00074 {
00075 last_robot_status_ = msg;
00076 }
00077
00078 void JointTrajectoryAction::watchdog(const ros::TimerEvent &e)
00079 {
00080
00081 if (!last_trajectory_state_)
00082 {
00083 ROS_DEBUG("Waiting for subscription to joint trajectory state");
00084 }
00085 if (!trajectory_state_recvd_)
00086 {
00087 ROS_DEBUG("Trajectory state not received since last watchdog");
00088 }
00089
00090
00091 if (has_active_goal_)
00092 {
00093 if (!trajectory_state_recvd_)
00094 {
00095
00096 if (!last_trajectory_state_)
00097 {
00098 ROS_WARN("Aborting goal because we have never heard a controller state message.");
00099 }
00100 else
00101 {
00102 ROS_WARN_STREAM(
00103 "Aborting goal because we haven't heard from the controller in " << WATCHD0G_PERIOD_ << " seconds");
00104 }
00105
00106 abortGoal();
00107
00108 }
00109 }
00110
00111
00112 trajectory_state_recvd_ = false;
00113 }
00114
00115 void JointTrajectoryAction::goalCB(JointTractoryActionServer::GoalHandle & gh)
00116 {
00117 ROS_INFO("Received new goal");
00118
00119 if (!gh.getGoal()->trajectory.points.empty())
00120 {
00121 if (industrial_utils::isSimilar(joint_names_, gh.getGoal()->trajectory.joint_names))
00122 {
00123
00124
00125 if (has_active_goal_)
00126 {
00127 ROS_WARN("Received new goal, canceling current goal");
00128 abortGoal();
00129 }
00130
00131
00132 if (withinGoalConstraints(last_trajectory_state_, gh.getGoal()->trajectory))
00133 {
00134
00135 ROS_INFO_STREAM("Already within goal constraints, setting goal succeeded");
00136 gh.setAccepted();
00137 gh.setSucceeded();
00138 has_active_goal_ = false;
00139
00140 }
00141 else
00142 {
00143 gh.setAccepted();
00144 active_goal_ = gh;
00145 has_active_goal_ = true;
00146
00147 ROS_INFO("Publishing trajectory");
00148
00149 current_traj_ = active_goal_.getGoal()->trajectory;
00150 pub_trajectory_command_.publish(current_traj_);
00151 }
00152 }
00153 else
00154 {
00155 ROS_ERROR("Joint trajectory action failing on invalid joints");
00156 control_msgs::FollowJointTrajectoryResult rslt;
00157 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00158 gh.setRejected(rslt, "Joint names do not match");
00159 }
00160 }
00161 else
00162 {
00163 ROS_ERROR("Joint trajectory action failed on empty trajectory");
00164 control_msgs::FollowJointTrajectoryResult rslt;
00165 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
00166 gh.setRejected(rslt, "Empty trajectory");
00167 }
00168
00169
00170 if (gh.getGoal()->goal_time_tolerance.toSec() > 0.0)
00171 {
00172 ROS_WARN_STREAM("Ignoring goal time tolerance in action goal, may be supported in the future");
00173 }
00174 if (!gh.getGoal()->goal_tolerance.empty())
00175 {
00176 ROS_WARN_STREAM(
00177 "Ignoring goal tolerance in action, using paramater tolerance of " << goal_threshold_ << " instead");
00178 }
00179 if (!gh.getGoal()->path_tolerance.empty())
00180 {
00181 ROS_WARN_STREAM("Ignoring goal path tolerance, option not supported by ROS-Industrial drivers");
00182 }
00183 }
00184
00185 void JointTrajectoryAction::cancelCB(JointTractoryActionServer::GoalHandle & gh)
00186 {
00187 ROS_DEBUG("Received action cancel request");
00188 if (active_goal_ == gh)
00189 {
00190
00191 trajectory_msgs::JointTrajectory empty;
00192 empty.joint_names = joint_names_;
00193 pub_trajectory_command_.publish(empty);
00194
00195
00196 active_goal_.setCanceled();
00197 has_active_goal_ = false;
00198 }
00199 else
00200 {
00201 ROS_WARN("Active goal and goal cancel do not match, ignoring cancel request");
00202 }
00203 }
00204
00205 void JointTrajectoryAction::controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
00206 {
00207
00208 last_trajectory_state_ = msg;
00209 trajectory_state_recvd_ = true;
00210
00211 if (!has_active_goal_)
00212 {
00213
00214 return;
00215 }
00216 if (current_traj_.points.empty())
00217 {
00218 ROS_DEBUG("Current trajectory is empty, ignoring feedback");
00219 return;
00220 }
00221
00222 if (!industrial_utils::isSimilar(joint_names_, msg->joint_names))
00223 {
00224 ROS_ERROR("Joint names from the controller don't match our joint names.");
00225 return;
00226 }
00227
00228
00229
00230
00231 ROS_DEBUG("Checking goal constraints");
00232 if (withinGoalConstraints(last_trajectory_state_, current_traj_))
00233 {
00234 if (last_robot_status_)
00235 {
00236
00237
00238
00239
00240 if (last_robot_status_->in_motion.val == industrial_msgs::TriState::FALSE)
00241 {
00242 ROS_INFO("Inside goal constraints, stopped moving, return success for action");
00243 active_goal_.setSucceeded();
00244 has_active_goal_ = false;
00245 }
00246 else if (last_robot_status_->in_motion.val == industrial_msgs::TriState::UNKNOWN)
00247 {
00248 ROS_INFO("Inside goal constraints, return success for action");
00249 ROS_WARN("Robot status in motion unknown, the robot driver node and controller code should be updated");
00250 active_goal_.setSucceeded();
00251 has_active_goal_ = false;
00252 }
00253 else
00254 {
00255 ROS_DEBUG("Within goal constraints but robot is still moving");
00256 }
00257 }
00258 else
00259 {
00260 ROS_INFO("Inside goal constraints, return success for action");
00261 ROS_WARN("Robot status is not being published the robot driver node and controller code should be updated");
00262 active_goal_.setSucceeded();
00263 has_active_goal_ = false;
00264 }
00265 }
00266 }
00267
00268 void JointTrajectoryAction::abortGoal()
00269 {
00270
00271 trajectory_msgs::JointTrajectory empty;
00272 pub_trajectory_command_.publish(empty);
00273
00274
00275 active_goal_.setAborted();
00276 has_active_goal_ = false;
00277 }
00278
00279 bool JointTrajectoryAction::withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00280 const trajectory_msgs::JointTrajectory & traj)
00281 {
00282 bool rtn = false;
00283 if (traj.points.empty())
00284 {
00285 ROS_WARN("Empty joint trajectory passed to check goal constraints, return false");
00286 rtn = false;
00287 }
00288 else
00289 {
00290 int last_point = traj.points.size() - 1;
00291
00292 if (industrial_robot_client::utils::isWithinRange(last_trajectory_state_->joint_names,
00293 last_trajectory_state_->actual.positions, traj.joint_names,
00294 traj.points[last_point].positions, goal_threshold_))
00295 {
00296 rtn = true;
00297 }
00298 else
00299 {
00300 rtn = false;
00301 }
00302 }
00303 return rtn;
00304 }
00305
00306 }
00307 }
00308