40 #include <rclcpp/duration.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/time.hpp>
44 #include <tf2_eigen/tf2_eigen.hpp>
51 : robot_model_(robot_model), group_(nullptr)
56 : robot_model_(robot_model), group_(
group.empty() ? nullptr : robot_model->getJointModelGroup(
group))
62 : robot_model_(robot_model), group_(
group)
71 this->waypoints_.clear();
72 for (
const auto& waypoint : other.waypoints_)
74 this->waypoints_.emplace_back(std::make_shared<moveit::core::RobotState>(*waypoint));
83 static const std::string EMPTY;
89 return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0);
94 if (duration_from_previous_.empty())
96 RCLCPP_WARN(rclcpp::get_logger(
"RobotTrajectory"),
"Too few waypoints to calculate a duration. Returning 0.");
101 if (duration_from_previous_[0] == 0)
103 if (duration_from_previous_.size() <= 1)
105 RCLCPP_WARN(rclcpp::get_logger(
"RobotTrajectory"),
"First and only waypoint has a duration of 0.");
109 return getDuration() /
static_cast<double>(duration_from_previous_.size() - 1);
112 return getDuration() /
static_cast<double>(duration_from_previous_.size());
117 robot_model_.swap(other.robot_model_);
118 std::swap(group_, other.group_);
119 waypoints_.swap(other.waypoints_);
120 duration_from_previous_.swap(other.duration_from_previous_);
125 end_index = std::min(end_index, source.waypoints_.size());
126 if (start_index >= end_index)
128 waypoints_.insert(waypoints_.end(), std::next(source.waypoints_.begin(), start_index),
129 std::next(source.waypoints_.begin(), end_index));
130 std::size_t index = duration_from_previous_.size();
131 duration_from_previous_.insert(duration_from_previous_.end(),
132 std::next(source.duration_from_previous_.begin(), start_index),
133 std::next(source.duration_from_previous_.begin(), end_index));
134 if (duration_from_previous_.size() > index)
135 duration_from_previous_[index] += dt;
142 std::reverse(waypoints_.begin(), waypoints_.end());
143 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
146 waypoint->invertVelocity();
148 if (!duration_from_previous_.empty())
150 duration_from_previous_.push_back(duration_from_previous_.front());
151 std::reverse(duration_from_previous_.begin(), duration_from_previous_.end());
152 duration_from_previous_.pop_back();
160 if (waypoints_.empty())
163 const std::vector<const moveit::core::JointModel*>& cont_joints =
169 double running_offset = 0.0;
170 double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
172 for (std::size_t j = 1; j < waypoints_.size(); ++j)
174 double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
175 if (last_value > current_value + M_PI)
176 running_offset += 2.0 * M_PI;
177 else if (current_value > last_value + M_PI)
178 running_offset -= 2.0 * M_PI;
180 last_value = current_value;
181 if (running_offset > std::numeric_limits<double>::epsilon() ||
182 running_offset < -std::numeric_limits<double>::epsilon())
184 current_value += running_offset;
185 waypoints_[j]->setJointPositions(cont_joint, ¤t_value);
189 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
197 if (waypoints_.empty())
200 const std::vector<const moveit::core::JointModel*>& cont_joints =
206 double reference_value = reference_value0;
207 cont_joint->enforcePositionBounds(&reference_value);
210 double running_offset = reference_value0 - reference_value;
212 double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
213 if (running_offset > std::numeric_limits<double>::epsilon() ||
214 running_offset < -std::numeric_limits<double>::epsilon())
216 double current_value = last_value + running_offset;
217 waypoints_[0]->setJointPositions(cont_joint, ¤t_value);
220 for (std::size_t j = 1; j < waypoints_.size(); ++j)
222 double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
223 if (last_value > current_value + M_PI)
224 running_offset += 2.0 * M_PI;
225 else if (current_value > last_value + M_PI)
226 running_offset -= 2.0 * M_PI;
228 last_value = current_value;
229 if (running_offset > std::numeric_limits<double>::epsilon() ||
230 running_offset < -std::numeric_limits<double>::epsilon())
232 current_value += running_offset;
233 waypoints_[j]->setJointPositions(cont_joint, ¤t_value);
237 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
244 const std::vector<std::string>& joint_filter)
const
246 trajectory = moveit_msgs::msg::RobotTrajectory();
247 if (waypoints_.empty())
249 const std::vector<const moveit::core::JointModel*>& jnts =
252 std::vector<const moveit::core::JointModel*> onedof;
253 std::vector<const moveit::core::JointModel*> mdof;
254 trajectory.joint_trajectory.joint_names.clear();
255 trajectory.multi_dof_joint_trajectory.joint_names.clear();
260 if (!joint_filter.empty() &&
261 std::find(joint_filter.begin(), joint_filter.end(), active_joint->getName()) == joint_filter.end())
264 if (active_joint->getVariableCount() == 1)
266 trajectory.joint_trajectory.joint_names.push_back(active_joint->getName());
267 onedof.push_back(active_joint);
271 trajectory.multi_dof_joint_trajectory.joint_names.push_back(active_joint->getName());
272 mdof.push_back(active_joint);
278 trajectory.joint_trajectory.header.frame_id = robot_model_->getModelFrame();
279 trajectory.joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
280 trajectory.joint_trajectory.points.resize(waypoints_.size());
285 trajectory.multi_dof_joint_trajectory.header.frame_id = robot_model_->getModelFrame();
286 trajectory.multi_dof_joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
287 trajectory.multi_dof_joint_trajectory.points.resize(waypoints_.size());
290 static const auto ZERO_DURATION = rclcpp::Duration::from_seconds(0);
291 double total_time = 0.0;
292 for (std::size_t i = 0; i < waypoints_.size(); ++i)
294 if (duration_from_previous_.size() > i)
295 total_time += duration_from_previous_[i];
299 trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
300 trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
302 for (std::size_t j = 0; j < onedof.size(); ++j)
304 trajectory.joint_trajectory.points[i].positions[j] =
305 waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
307 if (waypoints_[i]->hasVelocities())
308 trajectory.joint_trajectory.points[i].velocities.push_back(
309 waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
310 if (waypoints_[i]->hasAccelerations())
311 trajectory.joint_trajectory.points[i].accelerations.push_back(
312 waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
313 if (waypoints_[i]->hasEffort())
314 trajectory.joint_trajectory.points[i].effort.push_back(
315 waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
318 if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
319 trajectory.joint_trajectory.points[i].velocities.clear();
321 if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
322 trajectory.joint_trajectory.points[i].accelerations.clear();
324 if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
325 trajectory.joint_trajectory.points[i].effort.clear();
327 if (duration_from_previous_.size() > i)
328 trajectory.joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
330 trajectory.joint_trajectory.points[i].time_from_start = ZERO_DURATION;
334 trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
335 for (std::size_t j = 0; j < mdof.size(); ++j)
337 geometry_msgs::msg::TransformStamped ts = tf2::eigenToTransform(waypoints_[i]->getJointTransform(mdof[j]));
338 trajectory.multi_dof_joint_trajectory.points[i].transforms[j] = ts.transform;
340 if (waypoints_[i]->hasVelocities() && (mdof[j]->getType() == moveit::core::JointModel::JointType::PLANAR))
342 const std::vector<std::string> names = mdof[j]->getVariableNames();
343 const double* velocities = waypoints_[i]->getJointVelocities(mdof[j]);
345 geometry_msgs::msg::Twist point_velocity;
347 for (std::size_t k = 0; k < names.size(); ++k)
349 if (names[k].find(
"/x") != std::string::npos)
351 point_velocity.linear.x = velocities[k];
353 else if (names[k].find(
"/y") != std::string::npos)
355 point_velocity.linear.y = velocities[k];
357 else if (names[k].find(
"/z") != std::string::npos)
359 point_velocity.linear.z = velocities[k];
361 else if (names[k].find(
"/theta") != std::string::npos)
363 point_velocity.angular.z = velocities[k];
366 trajectory.multi_dof_joint_trajectory.points[i].velocities.push_back(point_velocity);
369 if (duration_from_previous_.size() > i)
370 trajectory.multi_dof_joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
372 trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ZERO_DURATION;
378 const trajectory_msgs::msg::JointTrajectory& trajectory)
383 std::size_t state_count = trajectory.points.size();
384 rclcpp::Time last_time_stamp = trajectory.header.stamp;
385 rclcpp::Time this_time_stamp = last_time_stamp;
387 for (std::size_t i = 0; i < state_count; ++i)
389 this_time_stamp = rclcpp::Time(trajectory.header.stamp) + trajectory.points[i].time_from_start;
390 auto st = std::make_shared<moveit::core::RobotState>(copy);
391 st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
392 if (!trajectory.points[i].velocities.empty())
393 st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
394 if (!trajectory.points[i].accelerations.empty())
395 st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
396 if (!trajectory.points[i].effort.empty())
397 st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
399 last_time_stamp = this_time_stamp;
406 const moveit_msgs::msg::RobotTrajectory& trajectory)
412 std::size_t state_count =
413 std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
414 rclcpp::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
415 trajectory.multi_dof_joint_trajectory.header.stamp :
416 trajectory.joint_trajectory.header.stamp;
417 rclcpp::Time this_time_stamp = last_time_stamp;
419 for (std::size_t i = 0; i < state_count; ++i)
421 auto st = std::make_shared<moveit::core::RobotState>(copy);
422 if (trajectory.joint_trajectory.points.size() > i)
424 st->setVariablePositions(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].positions);
425 if (!trajectory.joint_trajectory.points[i].velocities.empty())
426 st->setVariableVelocities(trajectory.joint_trajectory.joint_names,
427 trajectory.joint_trajectory.points[i].velocities);
428 if (!trajectory.joint_trajectory.points[i].accelerations.empty())
429 st->setVariableAccelerations(trajectory.joint_trajectory.joint_names,
430 trajectory.joint_trajectory.points[i].accelerations);
431 if (!trajectory.joint_trajectory.points[i].effort.empty())
432 st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
433 this_time_stamp = rclcpp::Time(trajectory.joint_trajectory.header.stamp) +
434 trajectory.joint_trajectory.points[i].time_from_start;
436 if (trajectory.multi_dof_joint_trajectory.points.size() > i)
438 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
440 Eigen::Isometry3d t = tf2::transformToEigen(trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
441 st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j], t);
443 this_time_stamp = rclcpp::Time(trajectory.multi_dof_joint_trajectory.header.stamp) +
444 trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
448 last_time_stamp = this_time_stamp;
454 const moveit_msgs::msg::RobotState& state,
455 const moveit_msgs::msg::RobotTrajectory& trajectory)
474 std::size_t index = 0, num_points = waypoints_.size();
475 double running_duration = 0.0;
476 for (; index < num_points; ++index)
478 running_duration += duration_from_previous_[index];
479 if (running_duration >= duration)
482 before = std::max<int>(index - 1, 0);
483 after = std::min<int>(index, num_points - 1);
486 double before_time = running_duration - duration_from_previous_[index];
490 blend = (duration - before_time) / duration_from_previous_[index];
495 if (duration_from_previous_.empty())
497 if (index >= duration_from_previous_.size())
498 index = duration_from_previous_.size() - 1;
501 for (std::size_t i = 0; i <= index; ++i)
502 time += duration_from_previous_[i];
512 moveit::core::RobotStatePtr& output_state)
const
518 int before = 0, after = 0;
523 waypoints_[before]->interpolate(*waypoints_[after], blend, *output_state);
532 out <<
"Empty trajectory.";
536 std::ios::fmtflags old_settings = out.flags();
537 int old_precision = out.precision();
538 out << std::fixed << std::setprecision(3);
540 out <<
"Trajectory has " << num_points <<
" points over " <<
getDuration() <<
" seconds\n";
542 if (variable_indexes.empty())
551 variable_indexes.resize(robot_model_->getVariableCount());
552 std::iota(variable_indexes.begin(), variable_indexes.end(), 0);
556 for (
size_t p_i = 0; p_i < num_points; ++p_i)
559 out <<
" waypoint " << std::setw(3) << p_i;
562 for (
int index : variable_indexes)
569 for (
int index : variable_indexes)
577 for (
int index : variable_indexes)
585 for (
int index : variable_indexes)
593 out.flags(old_settings);
594 out.precision(old_precision);
600 trajectory.
print(out);
606 auto trajectory_length = 0.0;
609 auto const& first = trajectory.
getWayPoint(index - 1);
610 auto const& second = trajectory.
getWayPoint(index);
611 trajectory_length += first.
distance(second);
613 return trajectory_length;
635 double acos_value = (
a *
a + b * b - cdist * cdist) / (2.0 *
a * b);
636 if (acos_value > -1.0 && acos_value < 1.0)
639 double angle = (M_PI - acos(acos_value));
642 double u = 2.0 * angle;
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::string & getName() const
Get the name of the joint group.
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints).
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
const double * getJointPositions(const std::string &joint_name) const
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & reverse()
void swap(robot_trajectory::RobotTrajectory &other)
double getWaypointDurationFromStart(std::size_t index) const
const std::string & getGroupName() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
RobotTrajectory(const moveit::core::RobotModelConstPtr &robot_model)
construct a trajectory for the whole robot
double getAverageSegmentDuration() const
void print(std::ostream &out, std::vector< int > variable_indexes=std::vector< int >()) const
Print information about the trajectory.
bool getStateAtDurationFromStart(const double request_duration, moveit::core::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory,...
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & unwind()
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::msg::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
RobotTrajectory & append(const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max())
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_in...
std::size_t getWayPointCount() const
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indices before and after a duration from start.
RobotTrajectory & clear()
const moveit::core::RobotState & getWayPoint(std::size_t index) const
double getDuration() const
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
double path_length(RobotTrajectory const &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
std::optional< double > waypoint_density(RobotTrajectory const &trajectory)
Calculate the waypoint density of a trajectory.
std::ostream & operator<<(std::ostream &out, const RobotTrajectory &trajectory)
Operator overload for printing trajectory to a stream.
std::optional< double > smoothness(RobotTrajectory const &trajectory)
Calculate the smoothness of a given trajectory.