37 katana_(katana), action_server_(
ros::NodeHandle(),
"katana_arm_controller/joint_trajectory_action",
39 action_server_follow_(
ros::NodeHandle(),
"katana_arm_controller/follow_joint_trajectory",
52 for (
size_t i = 0; i <
joints_.size(); ++i)
54 std::string ns = std::string(
"joint_trajectory_action_node/constraints") +
joints_[i];
90 hold[0].start_time = time.
toSec() - 0.001;
91 hold[0].duration = 0.0;
92 hold[0].splines.resize(
joints_.size());
93 for (
size_t j = 0; j <
joints_.size(); ++j)
94 hold[0].splines[j].coef[0] =
katana_->getMotorAngles()[j];
107 ROS_FATAL(
"The current trajectory can never be null");
112 if (traj.size() == 0)
114 ROS_ERROR(
"No segments in the trajectory");
122 while (seg + 1 < (
int)traj.size() && traj[seg + 1].start_time <= time.
toSec())
136 for (
size_t i = 0; i < q.size(); ++i)
139 q[i], qd[i], qdd[i]);
144 std::vector<double> error(
joints_.size());
145 for (
size_t i = 0; i <
joints_.size(); ++i)
147 error[i] =
katana_->getMotorAngles()[i] - q[i];
152 control_msgs::JointTrajectoryControllerState msg;
155 for (
size_t j = 0; j <
joints_.size(); ++j)
156 msg.joint_names.push_back(
joints_[j]);
157 msg.desired.positions.resize(
joints_.size());
158 msg.desired.velocities.resize(
joints_.size());
159 msg.desired.accelerations.resize(
joints_.size());
160 msg.actual.positions.resize(
joints_.size());
161 msg.actual.velocities.resize(
joints_.size());
163 msg.error.positions.resize(
joints_.size());
164 msg.error.velocities.resize(
joints_.size());
167 msg.header.stamp = time;
168 for (
size_t j = 0; j <
joints_.size(); ++j)
170 msg.desired.positions[j] = q[j];
171 msg.desired.velocities[j] = qd[j];
172 msg.desired.accelerations[j] = qdd[j];
173 msg.actual.positions[j] =
katana_->getMotorAngles()[j];
174 msg.actual.velocities[j] =
katana_->getMotorVelocities()[j];
176 msg.error.positions[j] = error[j];
177 msg.error.velocities[j] =
katana_->getMotorVelocities()[j] - qd[j];
193 ROS_WARN(
"commandCB() called, this is not tested yet");
197 JTAC action_client(
"katana_arm_controller/joint_trajectory_action",
true);
201 goal.trajectory = *(msg.get());
208 const trajectory_msgs::JointTrajectory &msg)
212 bool allPointsHaveVelocities =
true;
216 for (
size_t i = 0; i < msg.points.size(); i++)
218 if (msg.points[i].accelerations.size() != 0 && msg.points[i].accelerations.size() !=
joints_.size())
220 ROS_ERROR(
"Command point %d has %d elements for the accelerations", (
int)i, (
int)msg.points[i].accelerations.size());
223 if (msg.points[i].velocities.size() == 0)
226 allPointsHaveVelocities =
false;
228 else if (msg.points[i].velocities.size() !=
joints_.size())
230 ROS_ERROR(
"Command point %d has %d elements for the velocities", (
int)i, (
int)msg.points[i].velocities.size());
233 if (msg.points[i].positions.size() !=
joints_.size())
235 ROS_ERROR(
"Command point %d has %d elements for the positions", (
int)i, (
int)msg.points[i].positions.size());
242 if (lookup.size() == 0)
250 size_t steps = msg.points.size() - 1;
255 for (
size_t i = 0; i < steps; i++)
259 new_traj.push_back(seg);
262 for (
size_t j = 0; j <
joints_.size(); j++)
264 double times[steps + 1], positions[steps + 1], velocities[steps + 1], durations[steps], coeff0[steps],
265 coeff1[steps], coeff2[steps], coeff3[steps];
267 for (
size_t i = 0; i < steps + 1; i++)
269 times[i] = msg.header.stamp.toSec() + msg.points[i].time_from_start.toSec();
270 positions[i] = msg.points[i].positions[lookup[j]];
271 if (allPointsHaveVelocities)
272 velocities[i] = msg.points[i].velocities[lookup[j]];
273 ROS_DEBUG(
"position %zu for joint %zu in message (= our joint %d): %f", i, j, lookup[j], positions[i]);
276 for (
size_t i = 0; i < steps; i++)
278 durations[i] = times[i + 1] - times[i];
282 if (allPointsHaveVelocities)
284 ROS_DEBUG(
"Using getCubicSplineCoefficients()");
285 for (
size_t i = 0; i < steps; ++i)
287 std::vector<double> coeff;
290 coeff0[i] = coeff[0];
291 coeff1[i] = coeff[1];
292 coeff2[i] = coeff[2];
293 coeff3[i] = coeff[3];
302 for (
size_t i = 0; i < steps; ++i)
304 new_traj[i].duration = durations[i];
305 new_traj[i].start_time = times[i];
306 new_traj[i].splines[j].target_position = positions[i + 1];
307 new_traj[i].splines[j].coef[0] = coeff0[i];
308 new_traj[i].splines[j].coef[1] = coeff1[i];
309 new_traj[i].splines[j].coef[2] = coeff2[i];
310 new_traj[i].splines[j].coef[3] = coeff3[i];
314 ROS_DEBUG(
"The new trajectory has %d segments", (
int)new_traj.size());
315 for (
size_t i = 0; i < std::min((
size_t)20, new_traj.size()); i++)
317 ROS_DEBUG(
"Segment %2zu - start_time: %.3lf duration: %.3lf", i, new_traj[i].start_time, new_traj[i].duration);
318 for (
size_t j = 0; j < new_traj[i].splines.size(); ++j)
320 ROS_DEBUG(
" %.2lf %.2lf %.2lf %.2lf (%s)",
321 new_traj[i].splines[j].coef[0],
322 new_traj[i].splines[j].coef[1],
323 new_traj[i].splines[j].coef[2],
324 new_traj[i].splines[j].coef[3],
333 sprintf(filename,
"/tmp/trajectory-%zu.dat", j);
334 std::ofstream trajectory_file(filename, std::ios_base::out);
335 trajectory_file.precision(8);
336 for (
double t = new_traj[0].start_time; t < new_traj.back().start_time + new_traj.back().duration; t += 0.01)
340 while (seg + 1 < (
int)new_traj.size() && new_traj[seg + 1].start_time <= t)
347 double pos_t, vel_t, acc_t;
349 pos_t, vel_t, acc_t);
351 trajectory_file << t - new_traj[0].start_time <<
" " << pos_t <<
" " << vel_t <<
" " << acc_t << std::endl;
354 trajectory_file.close();
364 control_msgs::QueryTrajectoryState::Response &resp)
366 ROS_WARN(
"queryStateService() called, this is not tested yet");
372 ROS_FATAL(
"The current trajectory can never be null");
379 while (seg + 1 < (
int)traj.size() && traj[seg + 1].start_time <= req.time.toSec())
386 resp.name.resize(
joints_.size());
387 resp.position.resize(
joints_.size());
388 resp.velocity.resize(
joints_.size());
389 resp.acceleration.resize(
joints_.size());
390 for (
size_t j = 0; j <
joints_.size(); ++j)
394 resp.position[j], resp.velocity[j], resp.acceleration[j]);
403 static bool setsEqual(
const std::vector<std::string> &a,
const std::vector<std::string> &b)
405 if (a.size() != b.size())
408 for (
size_t i = 0; i < a.size(); ++i)
410 if (count(b.begin(), b.end(), a[i]) != 1)
413 for (
size_t i = 0; i < b.size(); ++i)
415 if (count(a.begin(), a.end(), b[i]) != 1)
431 ROS_WARN(
"joint_trajectory_action called while follow_joint_trajectory was active, canceling follow_joint_trajectory");
437 if (error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
450 ROS_WARN(
"follow_joint_trajectory called while joint_trajectory_action was active, canceling joint_trajectory_action");
457 FJTAS::Result result;
458 result.error_code = error_code;
460 if (error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
472 boost::function<
bool()> isPreemptRequested)
476 ROS_ERROR(
"Joints on incoming goal don't match our joints");
477 for (
size_t i = 0; i < trajectory.joint_names.size(); i++)
479 ROS_INFO(
" incoming joint %d: %s", (
int)i, trajectory.joint_names[i].c_str());
481 for (
size_t i = 0; i <
joints_.size(); i++)
485 return control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
488 if (isPreemptRequested())
490 ROS_WARN(
"New action goal already seems to have been canceled!");
498 if (trajectory.points.empty())
501 return control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
508 ROS_ERROR(
"Could not calculate new trajectory, aborting");
509 return control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
513 ROS_ERROR(
"Computed trajectory did not fulfill all constraints!");
514 return control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
521 "Sleeping for %f seconds before start of trajectory", (trajectory.header.stamp -
ros::Time::now()).
toSec());
523 while ((trajectory.header.stamp -
ros::Time::now()).toSec() > 0.5)
525 if (isPreemptRequested() || !
ros::ok())
527 ROS_WARN(
"Goal canceled by client while waiting until scheduled start, aborting!");
533 ROS_INFO(
"Sending trajectory to Katana arm...");
534 bool success =
katana_->executeTrajectory(new_traj, isPreemptRequested);
537 ROS_ERROR(
"Problem while transferring trajectory to Katana arm, aborting");
538 return control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
541 ROS_INFO(
"Waiting until goal reached...");
548 if (
katana_->someMotorCrashed())
550 ROS_ERROR(
"Some motor has crashed! Aborting trajectory...");
551 return control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
566 return control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
570 ROS_ERROR(
"Joints are idle and motors are not crashed, but we did not reach the goal position! WTF?");
571 return control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
575 if (isPreemptRequested())
577 ROS_WARN(
"Goal canceled by client while waiting for trajectory to finish, aborting!");
593 for (
size_t i = 0; i <
joints_.size(); i++)
598 ROS_WARN_STREAM(
"Joint " << i <<
" did not reach its goal. target position: " 600 <<
katana_->getMotorAngles()[i] << std::endl);
612 for (
size_t i = 0; i <
joints_.size(); i++)
623 std::vector<int> lookup(
joints_.size(), -1);
624 for (
size_t j = 0; j <
joints_.size(); ++j)
626 for (
size_t k = 0; k < msg.joint_names.size(); ++k)
628 if (msg.joint_names[k] ==
joints_[j])
637 ROS_ERROR(
"Unable to locate joint %s in the commanded trajectory.",
joints_[j].c_str());
638 return std::vector<int>();
653 const double MAX_SPEED = 2.21;
654 const double MIN_TIME = 0.01;
656 const double POSITION_TOLERANCE = 0.1;
662 for (
size_t seg = 0; seg < traj.size() - 1; seg++)
664 if (std::abs(traj[seg].start_time + traj[seg].duration - traj[seg + 1].start_time) > EPSILON)
666 ROS_ERROR(
"start time and duration of segment %zu do not match next segment", seg);
670 for (
size_t seg = 0; seg < traj.size(); seg++)
672 if (traj[seg].duration < MIN_TIME)
674 ROS_WARN(
"duration of segment %zu is too small: %f", seg, traj[seg].duration);
680 for (
size_t j = 0; j < traj[0].splines.size(); j++)
682 if (std::abs(traj[0].splines[j].coef[0] -
katana_->getMotorAngles()[j]) > POSITION_TOLERANCE)
684 ROS_ERROR(
"Initial joint angle of trajectory (%f) does not match current joint angle (%f) (joint %zu)", traj[0].splines[j].coef[0],
katana_->getMotorAngles()[j], j);
690 for (
size_t j = 0; j < traj[0].splines.size(); j++)
692 if (std::abs(traj[0].splines[j].coef[1]) > EPSILON)
694 ROS_ERROR(
"Velocity at t = 0 is not 0: %f (joint %zu)", traj[0].splines[j].coef[1], j);
699 for (
size_t j = 0; j < traj[traj.size() - 1].splines.size(); j++)
701 size_t seg = traj.size() - 1;
704 if (std::abs(vel_t) > EPSILON)
706 ROS_ERROR(
"Velocity at t = N is not 0 (joint %zu)", j);
712 for (
size_t seg = 0; seg < traj.size() - 1; seg++)
714 for (
size_t j = 0; j < traj[seg].splines.size(); j++)
716 double pos_t, vel_t, acc_t;
719 if (std::abs(traj[seg + 1].splines[j].coef[0] - pos_t) > EPSILON)
721 ROS_ERROR(
"Position discontinuity at end of segment %zu (joint %zu)", seg, j);
724 if (std::abs(traj[seg + 1].splines[j].coef[1] - vel_t) > EPSILON)
726 ROS_ERROR(
"Velocity discontinuity at end of segment %zu (joint %zu)", seg, j);
733 for (
double t = traj[0].start_time; t < traj.back().start_time + traj.back().duration; t += 0.01)
737 while (seg + 1 < (
int)traj.size() && traj[seg + 1].start_time <= t)
744 for (
size_t j = 0; j < traj[seg].splines.size(); j++)
746 double pos_t, vel_t, acc_t;
752 if (std::abs(vel_t) > MAX_SPEED)
754 ROS_ERROR(
"Velocity %f too high at time %f (joint %zu)", vel_t, t, j);
void executeCB(const JTAS::GoalConstPtr &goal)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
int executeCommon(const trajectory_msgs::JointTrajectory &trajectory, boost::function< bool()> isPreemptRequested)
void publish(const boost::shared_ptr< M > &message) const
bool queryStateService(control_msgs::QueryTrajectoryState::Request &req, control_msgs::QueryTrajectoryState::Response &resp)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_command_
boost::shared_ptr< SpecifiedTrajectory > calculateTrajectory(const trajectory_msgs::JointTrajectory &msg)
ros::Publisher controller_state_publisher_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer serve_query_state_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< AbstractKatana > katana_
void commandCB(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void executeCBFollow(const FJTAS::GoalConstPtr &goal)
void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
std::vector< int > makeJointsLookup(const trajectory_msgs::JointTrajectory &msg)
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
std::vector< Segment > SpecifiedTrajectory
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static const size_t MOVE_BUFFER_SIZE
bool isPreemptRequested()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
JointTrajectoryActionController(boost::shared_ptr< AbstractKatana > katana)
void splineCoefficients(int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2, double *arr_p3, double *arr_p4)
void reset_trajectory_and_stop()
FJTAS action_server_follow_
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_COND(cond,...)
std::vector< std::string > joints_
bool validTrajectory(const SpecifiedTrajectory &traj)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
double stopped_velocity_tolerance_
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)
static bool setsEqual(const std::vector< std::string > &a, const std::vector< std::string > &b)
std::vector< Spline > splines
boost::shared_ptr< SpecifiedTrajectory > current_trajectory_
std::vector< double > goal_constraints_
virtual ~JointTrajectoryActionController()