Go to the documentation of this file.
39 namespace joint_trajectory_action
48 controller_alive_(false), has_moved_once_(false), name_(
"joint_trajectory_action")
98 ROS_WARN_NAMED(
name_,
"Aborting goal because we have never heard a controller state message.");
103 "Aborting goal because we haven't heard from the controller in " <<
WATCHDOG_PERIOD_ <<
" seconds");
117 ROS_ERROR_NAMED(
name_,
"Joint trajectory action rejected: waiting for (initial) feedback from controller");
118 control_msgs::FollowJointTrajectoryResult rslt;
119 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
120 gh.
setRejected(rslt,
"Waiting for (initial) feedback from controller");
126 if (!gh.
getGoal()->trajectory.points.empty())
154 control_msgs::FollowJointTrajectoryResult rslt;
155 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
162 control_msgs::FollowJointTrajectoryResult rslt;
163 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
168 if (gh.
getGoal()->goal_time_tolerance.toSec() > 0.0)
172 if (!gh.
getGoal()->goal_tolerance.empty())
175 "Ignoring goal tolerance in action, using paramater tolerance of " <<
goal_threshold_ <<
" instead");
177 if (!gh.
getGoal()->path_tolerance.empty())
189 trajectory_msgs::JointTrajectory empty;
199 ROS_WARN_NAMED(
name_,
"Active goal and goal cancel do not match, ignoring cancel request");
232 ROS_INFO_NAMED(
name_,
"Waiting to check for goal completion until halfway through trajectory");
250 ROS_INFO_NAMED(
"joint_trajectory_action.controllerStateCB",
"Inside goal constraints - stopped moving- return success for action");
257 ROS_WARN_NAMED(
name_,
"Robot status in motion unknown, the robot driver node and controller code should be updated");
269 ROS_WARN_NAMED(
name_,
"Robot status is not being published the robot driver node and controller code should be updated");
279 trajectory_msgs::JointTrajectory empty;
288 const trajectory_msgs::JointTrajectory & traj)
291 if (traj.points.empty())
293 ROS_WARN_NAMED(
name_,
"Empty joint trajectory passed to check goal constraints, return false");
298 int last_point = traj.points.size() - 1;
ros::Subscriber sub_trajectory_state_
Subscribes to trajectory feedback (typically published by the robot driver).
bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, const trajectory_msgs::JointTrajectory &traj)
Controller status callback (executed when robot status message received)
boost::shared_ptr< const Goal > getGoal() const
void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
Controller state callback (executed when feedback message received)
#define ROS_DEBUG_STREAM_NAMED(name, args)
~JointTrajectoryAction()
Destructor.
ros::NodeHandle node_
Internal ROS node handle.
control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_
Cache of the last subscribed feedback message.
void goalCB(JointTractoryActionServer::GoalHandle gh)
Action server goal callback method.
ros::Publisher pub_trajectory_command_
Publishes desired trajectory (typically to the robot driver)
bool getJointNames(const std::string joint_list_param, const std::string urdf_param, std::vector< std::string > &joint_names)
#define ROS_ERROR_NAMED(name,...)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
double goal_threshold_
The goal joint threshold used for determining if a robot is near it final destination....
ros::Subscriber sub_robot_status_
Subscribes to the robot status (typically published by the robot driver).
JointTrajectoryAction()
Constructor.
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Timer watchdog_timer_
Watchdog time used to fail the action request if the robot driver is not responding.
bool isSimilar(std::vector< std::string > lhs, std::vector< std::string > rhs)
void watchdog(const ros::TimerEvent &e)
Watch dog callback, used to detect robot driver failures.
industrial_msgs::RobotStatusConstPtr last_robot_status_
Cache of the last subscribed status message.
ros::Time time_to_check_
Time at which to start checking for completion of current goal, if one is active.
#define ROS_INFO_NAMED(name,...)
void setAccepted(const std::string &text=std::string(""))
#define ROS_DEBUG_NAMED(name,...)
void abortGoal()
Aborts the current action goal and sends a stop command (empty message) to the robot driver.
bool has_moved_once_
Indicates that the robot has been in a moving state at least once since starting the current active t...
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void cancelCB(JointTractoryActionServer::GoalHandle gh)
Action server cancel callback method.
JointTractoryActionServer action_server_
Internal action server.
#define ROS_WARN_STREAM_NAMED(name, args)
bool isWithinRange(const std::vector< double > &lhs, const std::vector< double > &rhs, double full_range)
Checks to see if members are within the same range. Specifically, Each item in abs(lhs[i] - rhs[i]) <...
static const double DEFAULT_GOAL_THRESHOLD_
The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e....
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
#define ROS_WARN_NAMED(name,...)
std::string name_
Name of this class, for logging namespacing.
T param(const std::string ¶m_name, const T &default_val) const
trajectory_msgs::JointTrajectory current_traj_
Cache of the current active trajectory.
std::vector< std::string > joint_names_
The joint names associated with the robot the action is interfacing with. The joint names must be the...
#define ROS_INFO_STREAM_NAMED(name, args)
bool has_active_goal_
Indicates action has an active goal.
static const double WATCHDOG_PERIOD_
The watchdog period (seconds)
bool controller_alive_
Controller was alive during the last watchdog interval.
JointTractoryActionServer::GoalHandle active_goal_
Cache of the current active goal.
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg)
Controller status callback (executed when robot status message received)