51 for (
int i=1; i<=n; i++)
53 powers[i] = powers[i-1]*x;
58 double end_pos,
double end_vel,
double end_acc,
double time, std::vector<double>& coefficients)
60 coefficients.resize(6);
64 coefficients[0] = end_pos;
65 coefficients[1] = end_vel;
66 coefficients[2] = 0.5*end_acc;
67 coefficients[3] = 0.0;
68 coefficients[4] = 0.0;
69 coefficients[5] = 0.0;
76 coefficients[0] = start_pos;
77 coefficients[1] = start_vel;
78 coefficients[2] = 0.5*start_acc;
79 coefficients[3] = (-20.0*start_pos + 20.0*end_pos - 3.0*start_acc*T[2] + end_acc*T[2] -
80 12.0*start_vel*T[1] - 8.0*end_vel*T[1]) / (2.0*T[3]);
81 coefficients[4] = (30.0*start_pos - 30.0*end_pos + 3.0*start_acc*T[2] - 2.0*end_acc*T[2] +
82 16.0*start_vel*T[1] + 14.0*end_vel*T[1]) / (2.0*T[4]);
83 coefficients[5] = (-12.0*start_pos + 12.0*end_pos - start_acc*T[2] + end_acc*T[2] -
84 6.0*start_vel*T[1] - 6.0*end_vel*T[1]) / (2.0*T[5]);
92 double& position,
double& velocity,
double& acceleration)
98 position = t[0]*coefficients[0] +
99 t[1]*coefficients[1] +
100 t[2]*coefficients[2] +
101 t[3]*coefficients[3] +
102 t[4]*coefficients[4] +
103 t[5]*coefficients[5];
105 velocity = t[0]*coefficients[1] +
106 2.0*t[1]*coefficients[2] +
107 3.0*t[2]*coefficients[3] +
108 4.0*t[3]*coefficients[4] +
109 5.0*t[4]*coefficients[5];
111 acceleration = 2.0*t[0]*coefficients[2] +
112 6.0*t[1]*coefficients[3] +
113 12.0*t[2]*coefficients[4] +
114 20.0*t[3]*coefficients[5];
118 double end_pos,
double end_vel,
double time, std::vector<double>& coefficients)
120 coefficients.resize(4);
124 coefficients[0] = end_pos;
125 coefficients[1] = end_vel;
126 coefficients[2] = 0.0;
127 coefficients[3] = 0.0;
134 coefficients[0] = start_pos;
135 coefficients[1] = start_vel;
136 coefficients[2] = (-3.0*start_pos + 3.0*end_pos - 2.0*start_vel*T[1] - end_vel*T[1]) / T[2];
137 coefficients[3] = (2.0*start_pos - 2.0*end_pos + start_vel*T[1] + end_vel*T[1]) / T[3];
142 JointSplineTrajectoryController::JointSplineTrajectoryController()
143 : loop_count_(0), robot_(NULL)
171 for (
int i = 0; i < joint_names.
size(); ++i)
174 if (name_value.
getType() != XmlRpcValue::TypeString)
176 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
183 ROS_ERROR(
"Joint not found: %s. (namespace: %s)",
191 for (
size_t i = 0; i <
joints_.size(); ++i)
195 ROS_ERROR(
"Joint %s was not calibrated (namespace: %s)",
202 std::string gains_ns;
206 for (
size_t i = 0; i <
joints_.size(); ++i)
214 traj[0].duration = 0.0;
215 traj[0].splines.resize(
joints_.size());
216 for (
size_t j = 0; j <
joints_.size(); ++j)
217 traj[0].splines[j].coef[0] = 0.0;
230 (
node_,
"state", 1));
232 for (
size_t j = 0; j <
joints_.size(); ++j)
251 for (
size_t i = 0; i <
pids_.size(); ++i)
258 hold[0].duration = 0.0;
259 hold[0].splines.resize(
joints_.size());
260 for (
size_t j = 0; j <
joints_.size(); ++j)
261 hold[0].splines[j].coef[0] =
joints_[j]->position_;
277 ROS_FATAL(
"The current trajectory can never be null");
284 while (seg + 1 < (
int)traj.size() &&
285 traj[seg+1].start_time < time.
toSec())
292 if (traj.size() == 0)
293 ROS_ERROR(
"No segments in the trajectory");
295 ROS_ERROR(
"No earlier segments. First segment starts at %.3lf (now = %.3lf)", traj[0].start_time, time.
toSec());
301 for (
size_t i = 0; i <
q.size(); ++i)
304 time.
toSec() - traj[seg].start_time,
311 for (
size_t i = 0; i <
joints_.size(); ++i)
325 for (
size_t j = 0; j <
joints_.size(); ++j)
345 ROS_DEBUG(
"Figuring out new trajectory at %.3lf, with data from %.3lf",
346 time.
toSec(), msg->header.stamp.toSec());
353 if (msg->points.empty())
361 std::vector<int> lookup(
joints_.size(), -1);
362 for (
size_t j = 0; j <
joints_.size(); ++j)
364 for (
size_t k = 0; k < msg->joint_names.size(); ++k)
366 if (msg->joint_names[k] ==
joints_[j]->joint_->name)
375 ROS_ERROR(
"Unable to locate joint %s in the commanded trajectory.",
joints_[j]->joint_->name.c_str());
386 ROS_FATAL(
"The current trajectory can never be null");
394 int first_useful = -1;
395 while (first_useful + 1 < (
int)prev_traj.size() &&
396 prev_traj[first_useful + 1].start_time <= time.
toSec())
402 int last_useful = -1;
403 double msg_start_time;
404 if (msg->points.size() > 0)
405 msg_start_time = (msg->header.stamp + msg->points[0].time_from_start).toSec();
407 msg_start_time = std::max(time.
toSec(), msg->header.stamp.toSec());
409 while (last_useful + 1 < (
int)prev_traj.size() &&
410 prev_traj[last_useful + 1].start_time < msg_start_time)
415 if (last_useful < first_useful)
416 first_useful = last_useful;
419 for (
int i = std::max(first_useful,0); i <= last_useful; ++i)
421 new_traj.push_back(prev_traj[i]);
426 if (new_traj.size() == 0)
427 new_traj.push_back(prev_traj[prev_traj.size() - 1]);
432 Segment &last = new_traj[new_traj.size() - 1];
433 std::vector<double> prev_positions(
joints_.size());
434 std::vector<double> prev_velocities(
joints_.size());
435 std::vector<double> prev_accelerations(
joints_.size());
437 ROS_DEBUG(
"Initial conditions for new set of splines:");
438 for (
size_t i = 0; i <
joints_.size(); ++i)
442 prev_positions[i], prev_velocities[i], prev_accelerations[i]);
443 ROS_DEBUG(
" %.2lf, %.2lf, %.2lf (%s)", prev_positions[i], prev_velocities[i],
444 prev_accelerations[i],
joints_[i]->joint_->name.c_str());
449 std::vector<double> positions;
450 std::vector<double> velocities;
451 std::vector<double> accelerations;
453 std::vector<double> durations(msg->points.size());
454 durations[0] = msg->points[0].time_from_start.toSec();
455 for (
size_t i = 1; i < msg->points.size(); ++i)
456 durations[i] = (msg->points[i].time_from_start - msg->points[i-1].time_from_start).toSec();
459 std::vector<double> wrap(
joints_.size(), 0.0);
460 assert(!msg->points[0].positions.empty());
461 for (
size_t j = 0; j <
joints_.size(); ++j)
463 if (
joints_[j]->joint_->type == urdf::Joint::CONTINUOUS)
466 wrap[j] = (prev_positions[j] + dist) - msg->points[0].positions[j];
470 for (
size_t i = 0; i < msg->points.size(); ++i)
474 seg.
start_time = (msg->header.stamp + msg->points[i].time_from_start).toSec() - durations[i];
480 if (msg->points[i].accelerations.size() != 0 && msg->points[i].accelerations.size() !=
joints_.size())
482 ROS_ERROR(
"Command point %d has %d elements for the accelerations", (
int)i, (
int)msg->points[i].accelerations.size());
485 if (msg->points[i].velocities.size() != 0 && msg->points[i].velocities.size() !=
joints_.size())
487 ROS_ERROR(
"Command point %d has %d elements for the velocities", (
int)i, (
int)msg->points[i].velocities.size());
490 if (msg->points[i].positions.size() !=
joints_.size())
492 ROS_ERROR(
"Command point %d has %d elements for the positions", (
int)i, (
int)msg->points[i].positions.size());
498 accelerations.resize(msg->points[i].accelerations.size());
499 velocities.resize(msg->points[i].velocities.size());
500 positions.resize(msg->points[i].positions.size());
501 for (
size_t j = 0; j <
joints_.size(); ++j)
503 if (!accelerations.empty()) accelerations[j] = msg->points[i].accelerations[lookup[j]];
504 if (!velocities.empty()) velocities[j] = msg->points[i].velocities[lookup[j]];
505 if (!positions.empty()) positions[j] = msg->points[i].positions[lookup[j]] + wrap[j];
510 for (
size_t j = 0; j <
joints_.size(); ++j)
512 if (prev_accelerations.size() > 0 && accelerations.size() > 0)
515 prev_positions[j], prev_velocities[j], prev_accelerations[j],
516 positions[j], velocities[j], accelerations[j],
520 else if (prev_velocities.size() > 0 && velocities.size() > 0)
523 prev_positions[j], prev_velocities[j],
524 positions[j], velocities[j],
527 seg.
splines[j].coef.resize(6, 0.0);
531 seg.
splines[j].coef[0] = prev_positions[j];
532 if (durations[i] == 0.0)
535 seg.
splines[j].coef[1] = (positions[j] - prev_positions[j]) / durations[i];
545 new_traj.push_back(seg);
549 prev_positions = positions;
550 prev_velocities = velocities;
551 prev_accelerations = accelerations;
558 ROS_ERROR(
"The new trajectory was null!");
563 ROS_DEBUG(
"The new trajectory has %d segments", (
int)new_traj.size());
565 for (
size_t i = 0; i < std::min((
size_t)20,new_traj.size()); ++i)
567 ROS_DEBUG(
"Segment %2d: %.3lf for %.3lf", i, new_traj[i].start_time, new_traj[i].duration);
568 for (
size_t j = 0; j < new_traj[i].splines.size(); ++j)
570 ROS_DEBUG(
" %.2lf %.2lf %.2lf %.2lf , %.2lf %.2lf(%s)",
571 new_traj[i].splines[j].coef[0],
572 new_traj[i].splines[j].coef[1],
573 new_traj[i].splines[j].coef[2],
574 new_traj[i].splines[j].coef[3],
575 new_traj[i].splines[j].coef[4],
576 new_traj[i].splines[j].coef[5],
577 joints_[j]->joint_->name_.c_str());
584 pr2_controllers_msgs::QueryTrajectoryState::Request &req,
585 pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
591 ROS_FATAL(
"The current trajectory can never be null");
598 while (seg + 1 < (
int)traj.size() &&
599 traj[seg+1].start_time < req.time.toSec())
606 for (
size_t i = 0; i <
q.size(); ++i)
611 resp.name.resize(
joints_.size());
612 resp.position.resize(
joints_.size());
613 resp.velocity.resize(
joints_.size());
614 resp.acceleration.resize(
joints_.size());
615 for (
size_t j = 0; j <
joints_.size(); ++j)
617 resp.name[j] =
joints_[j]->joint_->name;
619 req.time.toSec() - traj[seg].start_time,
620 resp.position[j], resp.velocity[j], resp.acceleration[j]);
627 const std::vector<double>& coefficients,
double duration,
double time,
628 double& position,
double& velocity,
double& acceleration)
637 else if (time > duration)
647 position, velocity, acceleration);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
realtime_tools::RealtimeBox< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
ros::Subscriber sub_command_
~JointSplineTrajectoryController()
static void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
std::vector< pr2_mechanism_model::JointState * > joints_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
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)
Type const & getType() const
std::vector< control_toolbox::Pid > pids_
pr2_mechanism_model::RobotState * robot_
static void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
static void generatePowers(int n, double x, double *powers)
const std::string & getNamespace() const
bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req, pr2_controllers_msgs::QueryTrajectoryState::Response &resp)
JointState * getJointState(const std::string &name)
std::vector< double > qdd
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointTrajectoryControllerState > > controller_state_publisher_
bool getParam(const std::string &key, std::string &s) const
std::vector< Segment > SpecifiedTrajectory
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
ros::ServiceServer serve_query_state_
std::vector< Spline > splines
void commandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
if((endptr==val_str)||(endptr< (val_str+strlen(val_str))))
def shortest_angular_distance(from_angle, to_angle)