32 #include <boost/bind.hpp> 37 #include <trajectory_msgs/JointTrajectory.h> 38 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 39 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h> 62 if (!pn.
getParam(
"joints", joint_names))
72 for (
int i = 0; i < joint_names.
size(); ++i)
75 if (name_value.
getType() != XmlRpcValue::TypeString)
77 ROS_FATAL(
"Array of joint names should contain all strings. (namespace: %s)",
90 std::string ns = std::string(
"constraints/") +
joint_names_[i];
92 pn.
param(ns +
"/goal", g, -1.0);
93 pn.
param(ns +
"/trajectory", t, -1.0);
111 if (started_waiting_for_controller !=
ros::Time(0) &&
114 ROS_WARN(
"Waited for the controller for 30 seconds, but it never showed up.");
115 started_waiting_for_controller =
ros::Time(0);
132 static bool setsEqual(
const std::vector<std::string> &a,
const std::vector<std::string> &b)
134 if (a.size() != b.size())
137 for (
size_t i = 0; i < a.size(); ++i)
139 if (count(b.begin(), b.end(), a[i]) != 1)
142 for (
size_t i = 0; i < b.size(); ++i)
144 if (count(a.begin(), a.end(), b[i]) != 1)
158 bool should_abort =
false;
162 ROS_WARN(
"Aborting goal because we have never heard a controller state message.");
167 ROS_WARN(
"Aborting goal because we haven't heard from the controller in %.3lf seconds",
174 trajectory_msgs::JointTrajectory empty;
190 ROS_ERROR(
"Joints on incoming goal don't match our joints");
199 trajectory_msgs::JointTrajectory empty;
222 trajectory_msgs::JointTrajectory empty;
253 last_controller_state_ = msg;
256 if (!has_active_goal_)
258 if (current_traj_.points.empty())
260 if (now < current_traj_.header.stamp + current_traj_.points[0].time_from_start)
263 if (!
setsEqual(joint_names_, msg->joint_names))
265 ROS_ERROR(
"Joint names from the controller don't match our joint names.");
269 int last = current_traj_.points.size() - 1;
270 ros::Time end_time = current_traj_.header.stamp + current_traj_.points[last].time_from_start;
277 for (
size_t i = 0; i < msg->joint_names.size(); ++i)
279 double abs_error = fabs(msg->error.positions[i]);
280 double constraint = trajectory_constraints_[msg->joint_names[i]];
281 if (constraint >= 0 && abs_error > constraint)
284 trajectory_msgs::JointTrajectory empty;
286 pub_controller_command_.
publish(empty);
289 has_active_goal_ =
false;
290 ROS_WARN(
"Aborting because we would up outside the trajectory constraints");
298 bool inside_goal_constraints =
true;
299 for (
size_t i = 0; i < msg->joint_names.size() && inside_goal_constraints; ++i)
301 double abs_error = fabs(msg->error.positions[i]);
302 double goal_constraint = goal_constraints_[msg->joint_names[i]];
303 if (goal_constraint >= 0 && abs_error > goal_constraint)
304 inside_goal_constraints =
false;
307 if (fabs(msg->desired.velocities[i]) < 1e-6)
309 if (fabs(msg->actual.velocities[i]) > stopped_velocity_tolerance_)
310 inside_goal_constraints =
false;
314 if (inside_goal_constraints)
317 has_active_goal_ =
false;
319 else if (now < end_time +
ros::Duration(goal_time_constraint_))
325 ROS_WARN(
"Aborting because we wound up outside the goal constraints");
327 has_active_goal_ =
false;
335 int main(
int argc,
char** argv)
337 ros::init(argc, argv,
"joint_trajectory_action_node");
void watchdog(const ros::TimerEvent &e)
boost::shared_ptr< const Goal > getGoal() const
void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
ros::Publisher pub_controller_command_
std::map< std::string, double > goal_constraints_
JTAS::GoalHandle GoalHandle
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ros::Timer watchdog_timer_
void setAccepted(const std::string &text=std::string(""))
const double DEFAULT_GOAL_THRESHOLD
void goalCB(GoalHandle gh)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
void publish(const boost::shared_ptr< M > &message) const
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
JointTrajectoryExecuter(ros::NodeHandle &n)
bool getParam(const std::string &key, std::string &s) const
trajectory_msgs::JointTrajectory current_traj_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
ros::Subscriber sub_controller_state_
static bool setsEqual(const std::vector< std::string > &a, const std::vector< std::string > &b)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
std::vector< std::string > joint_names_
const std::string & getNamespace() const
int main(int argc, char **argv)
double stopped_velocity_tolerance_
void cancelCB(GoalHandle gh)
ROSCPP_DECL void spinOnce()
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
double goal_time_constraint_
std::map< std::string, double > trajectory_constraints_
~JointTrajectoryExecuter()