40 #include <boost/math/constants/constants.hpp> 46 : robot_model_(robot_model), group_(group.empty() ? nullptr : robot_model->getJointModelGroup(group))
65 static const std::string
empty;
88 end_index = std::min(end_index, source.
waypoints_.size());
89 if (start_index >= end_index)
92 std::next(source.
waypoints_.begin(), end_index));
104 for (robot_state::RobotStatePtr& waypoint :
waypoints_)
107 waypoint->invertVelocity();
122 const std::vector<const robot_model::JointModel*>& cont_joints =
125 for (std::size_t i = 0; i < cont_joints.size(); ++i)
128 double running_offset = 0.0;
129 double last_value =
waypoints_[0]->getJointPositions(cont_joints[i])[0];
131 for (std::size_t j = 1; j <
waypoints_.size(); ++j)
133 double current_value =
waypoints_[j]->getJointPositions(cont_joints[i])[0];
134 if (last_value > current_value + boost::math::constants::pi<double>())
135 running_offset += 2.0 * boost::math::constants::pi<double>();
136 else if (current_value > last_value + boost::math::constants::pi<double>())
137 running_offset -= 2.0 * boost::math::constants::pi<double>();
139 last_value = current_value;
140 if (running_offset > std::numeric_limits<double>::epsilon() ||
141 running_offset < -std::numeric_limits<double>::epsilon())
143 current_value += running_offset;
144 waypoints_[j]->setJointPositions(cont_joints[i], ¤t_value);
148 for (std::size_t j = 0; j <
waypoints_.size(); ++j)
157 const std::vector<const robot_model::JointModel*>& cont_joints =
160 for (std::size_t i = 0; i < cont_joints.size(); ++i)
163 double reference_value = reference_value0;
164 cont_joints[i]->enforcePositionBounds(&reference_value);
167 double running_offset = reference_value0 - reference_value;
169 double last_value =
waypoints_[0]->getJointPositions(cont_joints[i])[0];
170 if (running_offset > std::numeric_limits<double>::epsilon() ||
171 running_offset < -std::numeric_limits<double>::epsilon())
173 double current_value = last_value + running_offset;
174 waypoints_[0]->setJointPositions(cont_joints[i], ¤t_value);
177 for (std::size_t j = 1; j <
waypoints_.size(); ++j)
179 double current_value =
waypoints_[j]->getJointPositions(cont_joints[i])[0];
180 if (last_value > current_value + boost::math::constants::pi<double>())
181 running_offset += 2.0 * boost::math::constants::pi<double>();
182 else if (current_value > last_value + boost::math::constants::pi<double>())
183 running_offset -= 2.0 * boost::math::constants::pi<double>();
185 last_value = current_value;
186 if (running_offset > std::numeric_limits<double>::epsilon() ||
187 running_offset < -std::numeric_limits<double>::epsilon())
189 current_value += running_offset;
190 waypoints_[j]->setJointPositions(cont_joints[i], ¤t_value);
194 for (std::size_t j = 0; j <
waypoints_.size(); ++j)
206 trajectory = moveit_msgs::RobotTrajectory();
209 const std::vector<const robot_model::JointModel*>& jnt =
212 std::vector<const robot_model::JointModel*> onedof;
213 std::vector<const robot_model::JointModel*> mdof;
214 trajectory.joint_trajectory.joint_names.clear();
215 trajectory.multi_dof_joint_trajectory.joint_names.clear();
217 for (std::size_t i = 0; i < jnt.size(); ++i)
218 if (jnt[i]->getVariableCount() == 1)
220 trajectory.joint_trajectory.joint_names.push_back(jnt[i]->
getName());
221 onedof.push_back(jnt[i]);
225 trajectory.multi_dof_joint_trajectory.joint_names.push_back(jnt[i]->
getName());
226 mdof.push_back(jnt[i]);
230 trajectory.joint_trajectory.header.frame_id =
robot_model_->getModelFrame();
231 trajectory.joint_trajectory.header.stamp =
ros::Time(0);
232 trajectory.joint_trajectory.points.resize(
waypoints_.size());
237 trajectory.multi_dof_joint_trajectory.header.frame_id =
robot_model_->getModelFrame();
238 trajectory.multi_dof_joint_trajectory.header.stamp =
ros::Time(0);
239 trajectory.multi_dof_joint_trajectory.points.resize(
waypoints_.size());
243 double total_time = 0.0;
244 for (std::size_t i = 0; i <
waypoints_.size(); ++i)
251 trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
252 trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
254 for (std::size_t j = 0; j < onedof.size(); ++j)
256 trajectory.joint_trajectory.points[i].positions[j] =
257 waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
260 trajectory.joint_trajectory.points[i].velocities.push_back(
261 waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
263 trajectory.joint_trajectory.points[i].accelerations.push_back(
264 waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
266 trajectory.joint_trajectory.points[i].effort.push_back(
267 waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
270 if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
271 trajectory.joint_trajectory.points[i].velocities.clear();
273 if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
274 trajectory.joint_trajectory.points[i].accelerations.clear();
276 if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
277 trajectory.joint_trajectory.points[i].effort.clear();
280 trajectory.joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
282 trajectory.joint_trajectory.points[i].time_from_start = zero_duration;
286 trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
287 for (std::size_t j = 0; j < mdof.size(); ++j)
290 trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
292 if (
waypoints_[i]->hasVelocities() && (mdof[j]->getType() == robot_model::JointModel::JointType::PLANAR))
294 const std::vector<std::string> names = mdof[j]->getVariableNames();
295 const double* velocities =
waypoints_[i]->getJointVelocities(mdof[j]);
297 geometry_msgs::Twist point_velocity;
299 for (std::size_t k = 0; k < names.size(); ++k)
301 if (names[k].find(
"/x") != std::string::npos)
303 point_velocity.linear.x = velocities[k];
305 else if (names[k].find(
"/y") != std::string::npos)
307 point_velocity.linear.y = velocities[k];
309 else if (names[k].find(
"/z") != std::string::npos)
311 point_velocity.linear.z = velocities[k];
313 else if (names[k].find(
"/theta") != std::string::npos)
315 point_velocity.angular.z = velocities[k];
318 trajectory.multi_dof_joint_trajectory.points[i].velocities.push_back(point_velocity);
322 trajectory.multi_dof_joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
324 trajectory.multi_dof_joint_trajectory.points[i].time_from_start = zero_duration;
330 const trajectory_msgs::JointTrajectory&
trajectory)
335 std::size_t state_count = trajectory.points.size();
336 ros::Time last_time_stamp = trajectory.header.stamp;
337 ros::Time this_time_stamp = last_time_stamp;
339 for (std::size_t i = 0; i < state_count; ++i)
341 this_time_stamp = trajectory.header.stamp + trajectory.points[i].time_from_start;
343 st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
344 if (!trajectory.points[i].velocities.empty())
345 st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
346 if (!trajectory.points[i].accelerations.empty())
347 st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
348 if (!trajectory.points[i].effort.empty())
349 st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
351 last_time_stamp = this_time_stamp;
356 const moveit_msgs::RobotTrajectory&
trajectory)
362 std::size_t state_count =
363 std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
364 ros::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
365 trajectory.multi_dof_joint_trajectory.header.stamp :
366 trajectory.joint_trajectory.header.stamp;
367 ros::Time this_time_stamp = last_time_stamp;
369 for (std::size_t i = 0; i < state_count; ++i)
372 if (trajectory.joint_trajectory.points.size() > i)
374 st->setVariablePositions(trajectory.joint_trajectory.joint_names,
375 trajectory.joint_trajectory.points[i].positions);
376 if (!trajectory.joint_trajectory.points[i].velocities.empty())
377 st->setVariableVelocities(trajectory.joint_trajectory.joint_names,
378 trajectory.joint_trajectory.points[i].velocities);
379 if (!trajectory.joint_trajectory.points[i].accelerations.empty())
380 st->setVariableAccelerations(trajectory.joint_trajectory.joint_names,
381 trajectory.joint_trajectory.points[i].accelerations);
382 if (!trajectory.joint_trajectory.points[i].effort.empty())
383 st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
385 trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points[i].time_from_start;
387 if (trajectory.multi_dof_joint_trajectory.points.size() > i)
389 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
393 st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j], t);
395 this_time_stamp = trajectory.multi_dof_joint_trajectory.header.stamp +
396 trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
400 last_time_stamp = this_time_stamp;
405 const moveit_msgs::RobotState& state,
406 const moveit_msgs::RobotTrajectory&
trajectory)
426 double running_duration = 0.0;
427 for (; index < num_points; ++index)
430 if (running_duration >= duration)
433 before = std::max<int>(index - 1, 0);
434 after = std::min<int>(index, num_points - 1);
441 blend = (duration - before_time) / duration_from_previous_[index];
452 for (std::size_t i = 0; i <= index; ++i)
463 robot_state::RobotStatePtr& output_state)
const 469 int before = 0, after = 0;
Core components of MoveIt!
void swap(robot_trajectory::RobotTrajectory &other)
std::deque< robot_state::RobotStatePtr > waypoints_
const std::string & getGroupName() const
void setGroupName(const std::string &group_name)
const robot_model::JointModelGroup * group_
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
const std::string & getName() const
Get the name of the joint group.
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
robot_model::RobotModelConstPtr robot_model_
RobotTrajectory(const robot_model::RobotModelConstPtr &robot_model, const std::string &group)
std::string getName(void *handle)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory) const
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints). ...
bool getStateAtDurationFromStart(const double request_duration, robot_state::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation.
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Maintain a sequence of waypoints and the time durations between these waypoints.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt! robot state...
MOVEIT_DEPRECATED double getWaypointDurationFromStart(std::size_t index) const
double getAverageSegmentDuration() const
std::size_t getWayPointCount() const
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
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 double * getJointPositions(const std::string &joint_name) const
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indicies before and after a duration from start.
void addSuffixWayPoint(const robot_state::RobotState &state, double dt)
Add a point to the trajectory.
void setRobotTrajectoryMsg(const robot_state::RobotState &reference_state, const trajectory_msgs::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
std::deque< double > duration_from_previous_
void 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...