34 #include <boost/bind.hpp> 35 #include <boost/shared_ptr.hpp> 54 for (
int i=1;
i<=n;
i++)
56 powers[
i] = powers[
i-1]*x;
61 double end_pos,
double end_vel,
double end_acc,
double time, std::vector<double>& coefficients)
63 coefficients.resize(6);
67 coefficients[0] = end_pos;
68 coefficients[1] = end_vel;
69 coefficients[2] = 0.5*end_acc;
70 coefficients[3] = 0.0;
71 coefficients[4] = 0.0;
72 coefficients[5] = 0.0;
79 coefficients[0] = start_pos;
80 coefficients[1] = start_vel;
81 coefficients[2] = 0.5*start_acc;
82 coefficients[3] = (-20.0*start_pos + 20.0*end_pos - 3.0*start_acc*T[2] + end_acc*T[2] -
83 12.0*start_vel*T[1] - 8.0*end_vel*T[1]) / (2.0*T[3]);
84 coefficients[4] = (30.0*start_pos - 30.0*end_pos + 3.0*start_acc*T[2] - 2.0*end_acc*T[2] +
85 16.0*start_vel*T[1] + 14.0*end_vel*T[1]) / (2.0*T[4]);
86 coefficients[5] = (-12.0*start_pos + 12.0*end_pos - start_acc*T[2] + end_acc*T[2] -
87 6.0*start_vel*T[1] - 6.0*end_vel*T[1]) / (2.0*T[5]);
95 double& position,
double& velocity,
double& acceleration)
101 position = t[0]*coefficients[0] +
102 t[1]*coefficients[1] +
103 t[2]*coefficients[2] +
104 t[3]*coefficients[3] +
105 t[4]*coefficients[4] +
106 t[5]*coefficients[5];
108 velocity = t[0]*coefficients[1] +
109 2.0*t[1]*coefficients[2] +
110 3.0*t[2]*coefficients[3] +
111 4.0*t[3]*coefficients[4] +
112 5.0*t[4]*coefficients[5];
114 acceleration = 2.0*t[0]*coefficients[2] +
115 6.0*t[1]*coefficients[3] +
116 12.0*t[2]*coefficients[4] +
117 20.0*t[3]*coefficients[5];
121 double end_pos,
double end_vel,
double time, std::vector<double>& coefficients)
123 coefficients.resize(4);
127 coefficients[0] = end_pos;
128 coefficients[1] = end_vel;
129 coefficients[2] = 0.0;
130 coefficients[3] = 0.0;
137 coefficients[0] = start_pos;
138 coefficients[1] = start_vel;
139 coefficients[2] = (-3.0*start_pos + 3.0*end_pos - 2.0*start_vel*T[1] - end_vel*T[1]) / T[2];
140 coefficients[3] = (2.0*start_pos - 2.0*end_pos + start_vel*T[1] + end_vel*T[1]) / T[3];
146 : loop_count_(0), robot_(NULL)
176 for (
int i = 0;
i < joint_names.
size(); ++
i)
179 if (name_value.
getType() != XmlRpcValue::TypeString)
181 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
188 ROS_ERROR(
"Joint not found: %s. (namespace: %s)",
200 ROS_ERROR(
"Joint %s was not calibrated (namespace: %s)",
207 std::string gains_ns;
229 joint_nh.
param(
"proxy/acc_converge",
proxies_[
i].acc_converge_, 0.0);
231 joint_nh.
param(
"proxy/effort_limit",
proxies_[
i].effort_limit_, 0.0);
245 double stopped_velocity_tolerance;
246 node_.
param(
"joint_trajectory_action_node/constraints/stopped_velocity_tolerance", stopped_velocity_tolerance, 0.01);
251 std::string ns = std::string(
"joint_trajectory_action_node/constraints/") +
joints_[
i]->joint_->name;
260 std::string p =
"output_filters/" +
joints_[
i]->joint_->name;
273 traj[0].duration = 0.0;
274 traj[0].splines.resize(
joints_.size());
275 for (
size_t j = 0; j <
joints_.size(); ++j)
276 traj[0].splines[j].coef[0] = 0.0;
289 (
node_,
"state", 1));
291 for (
size_t j = 0; j <
joints_.size(); ++j)
323 for (
size_t i = 0;
i <
pids_.size(); ++
i) {
332 hold[0].duration = 0.0;
333 hold[0].splines.resize(
joints_.size());
334 for (
size_t j = 0; j <
joints_.size(); ++j)
335 hold[0].splines[j].coef[0] =
joints_[j]->position_;
352 ROS_FATAL(
"The current trajectory can never be null");
361 while (seg + 1 < (
int)traj.size() &&
362 traj[seg+1].start_time < time.
toSec())
369 if (traj.size() == 0)
370 ROS_ERROR(
"No segments in the trajectory");
372 ROS_ERROR(
"No earlier segments. First segment starts at %.3lf (now = %.3lf)", traj[0].start_time, time.
toSec());
378 for (
size_t i = 0;
i <
q.size(); ++
i)
381 time.
toSec() - traj[seg].start_time,
388 std::vector<double> v_error(
joints_.size());
406 effort =
pids_[i].computeCommand(
error[i], v_error[i], dt);
408 double effort_unfiltered = effort;
414 joints_[i]->commanded_effort_ = effort;
419 if ((traj[seg].gh && traj[seg].gh == current_active_goal) ||
420 (traj[seg].gh_follow && traj[seg].gh_follow == current_active_goal_follow))
422 ros::Time end_time(traj[seg].start_time + traj[seg].duration);
423 if (time <= end_time)
426 for (
size_t j = 0; j <
joints_.size(); ++j)
428 if (traj[seg].trajectory_tolerance[j].violated(
error[j], v_error[j]))
431 traj[seg].gh->setAborted();
432 else if (traj[seg].gh_follow) {
433 traj[seg].gh_follow->preallocated_result_->error_code =
434 control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
435 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
441 else if (seg == (
int)traj.size() - 1)
444 bool inside_goal_constraints =
true;
445 for (
size_t i = 0;
i <
joints_.size() && inside_goal_constraints; ++
i)
447 if (traj[seg].goal_tolerance[
i].violated(
error[
i], v_error[i]))
448 inside_goal_constraints =
false;
451 if (inside_goal_constraints)
456 traj[seg].gh->setSucceeded();
457 else if (traj[seg].gh_follow) {
458 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
459 traj[seg].gh_follow->setSucceeded(traj[seg].gh_follow->preallocated_result_);
463 else if (time < end_time +
ros::Duration(traj[seg].goal_time_tolerance))
473 traj[seg].gh->setAborted();
474 else if (traj[seg].gh_follow) {
475 traj[seg].gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
476 traj[seg].gh_follow->setAborted(traj[seg].gh_follow->preallocated_result_);
489 for (
size_t j = 0; j <
joints_.size(); ++j)
504 if (current_active_goal_follow)
506 current_active_goal_follow->preallocated_feedback_->header.stamp = time;
507 current_active_goal_follow->preallocated_feedback_->joint_names.resize(
joints_.size());
508 current_active_goal_follow->preallocated_feedback_->desired.positions.resize(
joints_.size());
509 current_active_goal_follow->preallocated_feedback_->desired.velocities.resize(
joints_.size());
510 current_active_goal_follow->preallocated_feedback_->desired.accelerations.resize(
joints_.size());
511 current_active_goal_follow->preallocated_feedback_->desired.effort.resize(
joints_.size());
512 current_active_goal_follow->preallocated_feedback_->actual.positions.resize(
joints_.size());
513 current_active_goal_follow->preallocated_feedback_->actual.velocities.resize(
joints_.size());
514 current_active_goal_follow->preallocated_feedback_->actual.effort.resize(
joints_.size());
515 current_active_goal_follow->preallocated_feedback_->error.positions.resize(
joints_.size());
516 current_active_goal_follow->preallocated_feedback_->error.velocities.resize(
joints_.size());
517 current_active_goal_follow->preallocated_feedback_->error.effort.resize(
joints_.size());
518 for (
size_t j = 0; j <
joints_.size(); ++j)
520 current_active_goal_follow->preallocated_feedback_->joint_names[j] =
joints_[j]->joint_->name;
521 current_active_goal_follow->preallocated_feedback_->desired.positions[j] =
q[j];
522 current_active_goal_follow->preallocated_feedback_->desired.velocities[j] =
qd[j];
523 current_active_goal_follow->preallocated_feedback_->desired.accelerations[j] =
qdd[j];
524 current_active_goal_follow->preallocated_feedback_->desired.effort[j] =
joints_[j]->commanded_effort_;
525 current_active_goal_follow->preallocated_feedback_->actual.positions[j] =
joints_[j]->position_;
526 current_active_goal_follow->preallocated_feedback_->actual.velocities[j] =
joints_[j]->velocity_;
527 current_active_goal_follow->preallocated_feedback_->actual.effort[j] =
joints_[j]->measured_effort_;
528 current_active_goal_follow->preallocated_feedback_->error.positions[j] =
error[j];
529 current_active_goal_follow->preallocated_feedback_->error.velocities[j] =
joints_[j]->velocity_ -
qd[j];
530 current_active_goal_follow->preallocated_feedback_->error.effort[j] =
joints_[j]->measured_effort_ -
joints_[j]->commanded_effort_;
532 const actionlib_msgs::GoalID goalID = current_active_goal_follow->gh_.getGoalID();
534 current_active_goal_follow->preallocated_feedback_->desired.time_from_start = time_from_start;
535 current_active_goal_follow->preallocated_feedback_->actual.time_from_start = time_from_start;
536 current_active_goal_follow->preallocated_feedback_->error.time_from_start = time_from_start;
537 current_active_goal_follow->gh_.publishFeedback(*current_active_goal_follow->preallocated_feedback_);
555 assert(!gh || !gh_follow);
557 ROS_DEBUG(
"Figuring out new trajectory at %.3lf, with data from %.3lf",
558 time.
toSec(), msg->header.stamp.toSec());
565 if (msg->points.empty())
579 for (
size_t j = 0; j <
joints_.size(); ++j)
582 for (
size_t k = 0;
k < gh_follow->gh_.getGoal()->path_tolerance.size(); ++
k)
584 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->path_tolerance[
k];
585 if (
joints_[j]->joint_->name == tol.name)
592 if (tol.position > 0)
593 trajectory_tolerance[j].position = tol.position;
594 else if (tol.position < 0)
595 trajectory_tolerance[j].position = 0.0;
597 if (tol.velocity > 0)
598 trajectory_tolerance[j].velocity = tol.velocity;
599 else if (tol.velocity < 0)
600 trajectory_tolerance[j].velocity = 0.0;
602 if (tol.acceleration > 0)
603 trajectory_tolerance[j].acceleration = tol.acceleration;
604 else if (tol.acceleration < 0)
605 trajectory_tolerance[j].acceleration = 0.0;
612 for (
size_t k = 0;
k < gh_follow->gh_.getGoal()->goal_tolerance.size(); ++
k)
614 const control_msgs::JointTolerance &tol = gh_follow->gh_.getGoal()->goal_tolerance[
k];
615 if (
joints_[j]->joint_->name == tol.name)
622 if (tol.position > 0)
623 goal_tolerance[j].position = tol.position;
624 else if (tol.position < 0)
625 goal_tolerance[j].position = 0.0;
627 if (tol.velocity > 0)
628 goal_tolerance[j].velocity = tol.velocity;
629 else if (tol.velocity < 0)
630 goal_tolerance[j].velocity = 0.0;
632 if (tol.acceleration > 0)
633 goal_tolerance[j].acceleration = tol.acceleration;
634 else if (tol.acceleration < 0)
635 goal_tolerance[j].acceleration = 0.0;
642 const ros::Duration &tol = gh_follow->gh_.getGoal()->goal_time_tolerance;
643 if (tol < ros::Duration(0.0))
644 goal_time_tolerance = 0.0;
645 else if (tol > ros::Duration(0.0))
646 goal_time_tolerance = tol.
toSec();
651 std::vector<int> lookup(
joints_.size(), -1);
652 for (
size_t j = 0; j <
joints_.size(); ++j)
654 for (
size_t k = 0;
k < msg->joint_names.size(); ++
k)
656 if (msg->joint_names[
k] ==
joints_[j]->joint_->name)
665 ROS_ERROR(
"Unable to locate joint %s in the commanded trajectory.",
joints_[j]->joint_->name.c_str());
668 else if (gh_follow) {
669 gh_follow->preallocated_result_->error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
670 gh_follow->setAborted(gh_follow->preallocated_result_);
682 ROS_FATAL(
"The current trajectory can never be null");
690 int first_useful = -1;
691 while (first_useful + 1 < (
int)prev_traj.size() &&
692 prev_traj[first_useful + 1].start_time <= time.
toSec())
698 int last_useful = -1;
699 double msg_start_time;
701 msg_start_time = time.
toSec();
703 msg_start_time = msg->header.stamp.toSec();
709 while (last_useful + 1 < (
int)prev_traj.size() &&
710 prev_traj[last_useful + 1].start_time < msg_start_time)
715 if (last_useful < first_useful)
716 first_useful = last_useful;
719 for (
int i = std::max(first_useful,0);
i <= last_useful; ++
i)
721 new_traj.push_back(prev_traj[
i]);
726 if (new_traj.size() == 0)
727 new_traj.push_back(prev_traj[prev_traj.size() - 1]);
732 Segment &last = new_traj[new_traj.size() - 1];
733 std::vector<double> prev_positions(
joints_.size());
734 std::vector<double> prev_velocities(
joints_.size());
735 std::vector<double> prev_accelerations(
joints_.size());
737 double t = (msg->header.stamp ==
ros::Time(0.0) ? time.
toSec() : msg->header.stamp.toSec())
739 ROS_DEBUG(
"Initial conditions at %.3f for new set of splines:", t);
744 prev_positions[
i], prev_velocities[i], prev_accelerations[i]);
745 ROS_DEBUG(
" %.2lf, %.2lf, %.2lf (%s)", prev_positions[i], prev_velocities[i],
746 prev_accelerations[i],
joints_[i]->joint_->name.c_str());
751 std::vector<double> positions;
752 std::vector<double> velocities;
753 std::vector<double> accelerations;
755 std::vector<double> durations(msg->points.size());
756 if (msg->points.size() > 0)
757 durations[0] = msg->points[0].time_from_start.toSec();
758 for (
size_t i = 1;
i < msg->points.size(); ++
i)
759 durations[
i] = (msg->points[
i].time_from_start - msg->points[
i-1].time_from_start).toSec();
762 std::vector<double> wrap(
joints_.size(), 0.0);
763 assert(!msg->points[0].positions.empty());
764 for (
size_t j = 0; j <
joints_.size(); ++j)
766 if (
joints_[j]->joint_->type == urdf::Joint::CONTINUOUS)
769 wrap[j] = (prev_positions[j] + dist) - msg->points[0].positions[lookup[j]];
773 for (
size_t i = 0;
i < msg->points.size(); ++
i)
778 seg.
start_time = (time + msg->points[
i].time_from_start).toSec() - durations[
i];
780 seg.
start_time = (msg->header.stamp + msg->points[
i].time_from_start).toSec() - durations[
i];
788 if (msg->points[
i].accelerations.size() != 0 && msg->points[
i].accelerations.size() !=
joints_.size())
790 ROS_ERROR(
"Command point %d has %d elements for the accelerations", (
int)
i, (
int)msg->points[i].accelerations.size());
793 if (msg->points[
i].velocities.size() != 0 && msg->points[
i].velocities.size() !=
joints_.size())
795 ROS_ERROR(
"Command point %d has %d elements for the velocities", (
int)
i, (
int)msg->points[i].velocities.size());
798 if (msg->points[
i].positions.size() !=
joints_.size())
800 ROS_ERROR(
"Command point %d has %d elements for the positions", (
int)
i, (
int)msg->points[i].positions.size());
806 accelerations.resize(msg->points[
i].accelerations.size());
807 velocities.resize(msg->points[
i].velocities.size());
808 positions.resize(msg->points[
i].positions.size());
809 for (
size_t j = 0; j <
joints_.size(); ++j)
811 if (!accelerations.empty()) accelerations[j] = msg->points[
i].accelerations[lookup[j]];
812 if (!velocities.empty()) velocities[j] = msg->points[
i].velocities[lookup[j]];
813 if (!positions.empty()) positions[j] = msg->points[
i].positions[lookup[j]] + wrap[j];
818 for (
size_t j = 0; j <
joints_.size(); ++j)
820 if (prev_accelerations.size() > 0 && accelerations.size() > 0)
823 prev_positions[j], prev_velocities[j], prev_accelerations[j],
824 positions[j], velocities[j], accelerations[j],
828 else if (prev_velocities.size() > 0 && velocities.size() > 0)
831 prev_positions[j], prev_velocities[j],
832 positions[j], velocities[j],
835 seg.
splines[j].coef.resize(6, 0.0);
839 seg.
splines[j].coef[0] = prev_positions[j];
840 if (durations[
i] == 0.0)
843 seg.
splines[j].coef[1] = (positions[j] - prev_positions[j]) / durations[
i];
858 new_traj.push_back(seg);
862 prev_positions = positions;
863 prev_velocities = velocities;
864 prev_accelerations = accelerations;
873 ROS_ERROR(
"The new trajectory was null!");
878 ROS_DEBUG(
"The new trajectory has %d segments", (
int)new_traj.size());
880 for (
size_t i = 0;
i < std::min((
size_t)20,new_traj.size()); ++
i)
882 ROS_DEBUG(
"Segment %2d: %.3lf for %.3lf",
i, new_traj[
i].start_time, new_traj[
i].duration);
883 for (
size_t j = 0; j < new_traj[
i].splines.size(); ++j)
885 ROS_DEBUG(
" %.2lf %.2lf %.2lf %.2lf , %.2lf %.2lf(%s)",
886 new_traj[
i].splines[j].coef[0],
887 new_traj[
i].splines[j].coef[1],
888 new_traj[
i].splines[j].coef[2],
889 new_traj[
i].splines[j].coef[3],
890 new_traj[
i].splines[j].coef[4],
891 new_traj[
i].splines[j].coef[5],
892 joints_[j]->joint_->name_.c_str());
899 pr2_controllers_msgs::QueryTrajectoryState::Request &req,
900 pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
906 ROS_FATAL(
"The current trajectory can never be null");
913 while (seg + 1 < (
int)traj.size() &&
914 traj[seg+1].start_time < req.time.toSec())
921 for (
size_t i = 0;
i <
q.size(); ++
i)
926 resp.name.resize(
joints_.size());
927 resp.position.resize(
joints_.size());
928 resp.velocity.resize(
joints_.size());
929 resp.acceleration.resize(
joints_.size());
930 for (
size_t j = 0; j <
joints_.size(); ++j)
932 resp.name[j] =
joints_[j]->joint_->name;
934 req.time.toSec() - traj[seg].start_time,
935 resp.position[j], resp.velocity[j], resp.acceleration[j]);
942 const std::vector<double>& coefficients,
double duration,
double time,
943 double& position,
double& velocity,
double& acceleration)
952 else if (time > duration)
962 position, velocity, acceleration);
966 static bool setsEqual(
const std::vector<std::string> &a,
const std::vector<std::string> &b)
968 if (a.size() != b.size())
971 for (
size_t i = 0;
i < a.size(); ++
i)
973 if (count(b.begin(), b.end(), a[
i]) != 1)
976 for (
size_t i = 0;
i < b.size(); ++
i)
978 if (count(a.begin(), a.end(), b[
i]) != 1)
991 if (current_active_goal)
995 current_active_goal->gh_.setCanceled();
997 if (current_active_goal_follow)
1000 current_active_goal_follow->gh_.setCanceled();
1005 template <
class Enclosure,
class Member>
1015 std::vector<std::string> joint_names(
joints_.size());
1016 for (
size_t j = 0; j <
joints_.size(); ++j)
1017 joint_names[j] =
joints_[j]->joint_->name;
1022 ROS_ERROR(
"Joints on incoming goal don't match our joints");
1041 std::vector<std::string> joint_names(
joints_.size());
1042 for (
size_t j = 0; j <
joints_.size(); ++j)
1043 joint_names[j] =
joints_[j]->joint_->name;
1048 ROS_ERROR(
"Joints on incoming goal don't match our joints");
1049 control_msgs::FollowJointTrajectoryResult result;
1050 result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
1072 if (current_active_goal && current_active_goal->gh_ == gh)
1076 trajectory_msgs::JointTrajectory::Ptr empty(
new trajectory_msgs::JointTrajectory);
1077 empty->joint_names.resize(
joints_.size());
1078 for (
size_t j = 0; j <
joints_.size(); ++j)
1079 empty->joint_names[j] =
joints_[j]->joint_->name;
1083 current_active_goal->gh_.setCanceled();
1090 if (current_active_goal && current_active_goal->gh_ == gh)
1094 trajectory_msgs::JointTrajectory::Ptr empty(
new trajectory_msgs::JointTrajectory);
1095 empty->joint_names.resize(
joints_.size());
1096 for (
size_t j = 0; j <
joints_.size(); ++j)
1097 empty->joint_names[j] =
joints_[j]->joint_->name;
1101 current_active_goal->gh_.setCanceled();
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
std::vector< Spline > splines
RTServerGoalHandle< pr2_controllers_msgs::JointTrajectoryAction > RTGoalHandle
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
boost::shared_ptr< const Goal > getGoal() const
static void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
static bool setsEqual(const std::vector< std::string > &a, const std::vector< std::string > &b)
std::vector< bool > proxies_enabled_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
std::vector< JointTolerance > default_goal_tolerance_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
static void sampleQuinticSpline(const std::vector< double > &coefficients, double time, double &position, double &velocity, double &acceleration)
Samples a quintic spline segment at a particular time.
void goalCBFollow(GoalHandleFollow gh)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
static boost::shared_ptr< Member > share_member(boost::shared_ptr< Enclosure > enclosure, Member &member)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::vector< JointTolerance > default_trajectory_tolerance_
static void getQuinticSplineCoefficients(double start_pos, double start_vel, double start_acc, double end_pos, double end_vel, double end_acc, double time, std::vector< double > &coefficients)
~JointTrajectoryActionController()
std::vector< control_toolbox::Pid > pids_
std::vector< JointTolerance > goal_tolerance
void setAccepted(const std::string &text=std::string(""))
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
boost::scoped_ptr< FJTAS > action_server_follow_
std::vector< double > masses_
void cancelCB(GoalHandle gh)
bool getParam(const std::string &key, std::string &s) const
static void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
if((endptr==val_str)||(endptr<(val_str+strlen(val_str))))
void cancelCBFollow(GoalHandleFollow gh)
void goalCB(GoalHandle gh)
static void generatePowers(int n, double x, double *powers)
pr2_mechanism_model::RobotState * robot_
JointTrajectoryActionController()
std::string resolveName(const std::string &name, bool remap=true) const
JointState * getJointState(const std::string &name)
boost::shared_ptr< RTGoalHandleFollow > rt_active_goal_follow_
bool hasParam(const std::string &key) const
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > FJTAS
boost::shared_ptr< RTGoalHandle > gh
std::vector< Segment > SpecifiedTrajectory
boost::shared_ptr< RTGoalHandle > rt_active_goal_
const std::string & getNamespace() const
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
boost::shared_ptr< RTGoalHandleFollow > gh_follow
RTServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RTGoalHandleFollow
void commandTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &traj, boost::shared_ptr< RTGoalHandle > gh=boost::shared_ptr< RTGoalHandle >((RTGoalHandle *) NULL), boost::shared_ptr< RTGoalHandleFollow > gh_follow=boost::shared_ptr< RTGoalHandleFollow >((RTGoalHandleFollow *) NULL))
std::vector< double > qdd
std::vector< control_toolbox::LimitedProxy > proxies_
ros::Timer goal_handle_timer_
ros::ServiceServer serve_query_state_
std::vector< JointTolerance > trajectory_tolerance
std::vector< boost::shared_ptr< filters::FilterChain< double > > > output_filters_
double default_goal_time_constraint_
boost::scoped_ptr< JTAS > action_server_
bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
double goal_time_tolerance
ros::Subscriber sub_command_
def shortest_angular_distance(from_angle, to_angle)
std::vector< pr2_mechanism_model::JointState * > joints_
void runNonRT(const ros::TimerEvent &te)