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;
92 end_index = std::min(end_index, source.
waypoints_.size());
93 if (start_index >= end_index)
96 std::next(source.
waypoints_.begin(), end_index));
108 for (robot_state::RobotStatePtr& waypoint :
waypoints_)
111 waypoint->invertVelocity();
126 const std::vector<const robot_model::JointModel*>& cont_joints =
129 for (std::size_t i = 0; i < cont_joints.size(); ++i)
132 double running_offset = 0.0;
133 double last_value =
waypoints_[0]->getJointPositions(cont_joints[i])[0];
135 for (std::size_t j = 1; j <
waypoints_.size(); ++j)
137 double current_value =
waypoints_[j]->getJointPositions(cont_joints[i])[0];
138 if (last_value > current_value + boost::math::constants::pi<double>())
139 running_offset += 2.0 * boost::math::constants::pi<double>();
140 else if (current_value > last_value + boost::math::constants::pi<double>())
141 running_offset -= 2.0 * boost::math::constants::pi<double>();
143 last_value = current_value;
144 if (running_offset > std::numeric_limits<double>::epsilon() ||
145 running_offset < -std::numeric_limits<double>::epsilon())
147 current_value += running_offset;
148 waypoints_[j]->setJointPositions(cont_joints[i], ¤t_value);
152 for (std::size_t j = 0; j <
waypoints_.size(); ++j)
161 const std::vector<const robot_model::JointModel*>& cont_joints =
164 for (std::size_t i = 0; i < cont_joints.size(); ++i)
167 double reference_value = reference_value0;
168 cont_joints[i]->enforcePositionBounds(&reference_value);
171 double running_offset = reference_value0 - reference_value;
173 double last_value =
waypoints_[0]->getJointPositions(cont_joints[i])[0];
174 if (running_offset > std::numeric_limits<double>::epsilon() ||
175 running_offset < -std::numeric_limits<double>::epsilon())
177 double current_value = last_value + running_offset;
178 waypoints_[0]->setJointPositions(cont_joints[i], ¤t_value);
181 for (std::size_t j = 1; j <
waypoints_.size(); ++j)
183 double current_value =
waypoints_[j]->getJointPositions(cont_joints[i])[0];
184 if (last_value > current_value + boost::math::constants::pi<double>())
185 running_offset += 2.0 * boost::math::constants::pi<double>();
186 else if (current_value > last_value + boost::math::constants::pi<double>())
187 running_offset -= 2.0 * boost::math::constants::pi<double>();
189 last_value = current_value;
190 if (running_offset > std::numeric_limits<double>::epsilon() ||
191 running_offset < -std::numeric_limits<double>::epsilon())
193 current_value += running_offset;
194 waypoints_[j]->setJointPositions(cont_joints[i], ¤t_value);
198 for (std::size_t j = 0; j <
waypoints_.size(); ++j)
209 const std::vector<std::string>& joint_filter)
const 211 trajectory = moveit_msgs::RobotTrajectory();
214 const std::vector<const robot_model::JointModel*>& jnt =
217 std::vector<const robot_model::JointModel*> onedof;
218 std::vector<const robot_model::JointModel*> mdof;
219 trajectory.joint_trajectory.joint_names.clear();
220 trajectory.multi_dof_joint_trajectory.joint_names.clear();
222 for (std::size_t i = 0; i < jnt.size(); ++i)
225 if (!joint_filter.empty() &&
226 std::find(joint_filter.begin(), joint_filter.end(), jnt[i]->getName()) == joint_filter.end())
229 if (jnt[i]->getVariableCount() == 1)
231 trajectory.joint_trajectory.joint_names.push_back(jnt[i]->
getName());
232 onedof.push_back(jnt[i]);
236 trajectory.multi_dof_joint_trajectory.joint_names.push_back(jnt[i]->
getName());
237 mdof.push_back(jnt[i]);
243 trajectory.joint_trajectory.header.frame_id =
robot_model_->getModelFrame();
244 trajectory.joint_trajectory.header.stamp =
ros::Time(0);
245 trajectory.joint_trajectory.points.resize(
waypoints_.size());
250 trajectory.multi_dof_joint_trajectory.header.frame_id =
robot_model_->getModelFrame();
251 trajectory.multi_dof_joint_trajectory.header.stamp =
ros::Time(0);
252 trajectory.multi_dof_joint_trajectory.points.resize(
waypoints_.size());
256 double total_time = 0.0;
257 for (std::size_t i = 0; i <
waypoints_.size(); ++i)
264 trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
265 trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
267 for (std::size_t j = 0; j < onedof.size(); ++j)
269 trajectory.joint_trajectory.points[i].positions[j] =
270 waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
273 trajectory.joint_trajectory.points[i].velocities.push_back(
274 waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
276 trajectory.joint_trajectory.points[i].accelerations.push_back(
277 waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
279 trajectory.joint_trajectory.points[i].effort.push_back(
280 waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
283 if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
284 trajectory.joint_trajectory.points[i].velocities.clear();
286 if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
287 trajectory.joint_trajectory.points[i].accelerations.clear();
289 if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
290 trajectory.joint_trajectory.points[i].effort.clear();
293 trajectory.joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
295 trajectory.joint_trajectory.points[i].time_from_start = ZERO_DURATION;
299 trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
300 for (std::size_t j = 0; j < mdof.size(); ++j)
303 trajectory.multi_dof_joint_trajectory.points[i].transforms[j] = ts.transform;
305 if (
waypoints_[i]->hasVelocities() && (mdof[j]->getType() == robot_model::JointModel::JointType::PLANAR))
307 const std::vector<std::string> names = mdof[j]->getVariableNames();
308 const double* velocities =
waypoints_[i]->getJointVelocities(mdof[j]);
310 geometry_msgs::Twist point_velocity;
312 for (std::size_t k = 0; k < names.size(); ++k)
314 if (names[k].find(
"/x") != std::string::npos)
316 point_velocity.linear.x = velocities[k];
318 else if (names[k].find(
"/y") != std::string::npos)
320 point_velocity.linear.y = velocities[k];
322 else if (names[k].find(
"/z") != std::string::npos)
324 point_velocity.linear.z = velocities[k];
326 else if (names[k].find(
"/theta") != std::string::npos)
328 point_velocity.angular.z = velocities[k];
331 trajectory.multi_dof_joint_trajectory.points[i].velocities.push_back(point_velocity);
335 trajectory.multi_dof_joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
337 trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ZERO_DURATION;
343 const trajectory_msgs::JointTrajectory& trajectory)
348 std::size_t state_count = trajectory.points.size();
349 ros::Time last_time_stamp = trajectory.header.stamp;
350 ros::Time this_time_stamp = last_time_stamp;
352 for (std::size_t i = 0; i < state_count; ++i)
354 this_time_stamp = trajectory.header.stamp + trajectory.points[i].time_from_start;
356 st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
357 if (!trajectory.points[i].velocities.empty())
358 st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
359 if (!trajectory.points[i].accelerations.empty())
360 st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
361 if (!trajectory.points[i].effort.empty())
362 st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
364 last_time_stamp = this_time_stamp;
369 const moveit_msgs::RobotTrajectory& trajectory)
375 std::size_t state_count =
376 std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
377 ros::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
378 trajectory.multi_dof_joint_trajectory.header.stamp :
379 trajectory.joint_trajectory.header.stamp;
380 ros::Time this_time_stamp = last_time_stamp;
382 for (std::size_t i = 0; i < state_count; ++i)
385 if (trajectory.joint_trajectory.points.size() > i)
387 st->setVariablePositions(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].positions);
388 if (!trajectory.joint_trajectory.points[i].velocities.empty())
389 st->setVariableVelocities(trajectory.joint_trajectory.joint_names,
390 trajectory.joint_trajectory.points[i].velocities);
391 if (!trajectory.joint_trajectory.points[i].accelerations.empty())
392 st->setVariableAccelerations(trajectory.joint_trajectory.joint_names,
393 trajectory.joint_trajectory.points[i].accelerations);
394 if (!trajectory.joint_trajectory.points[i].effort.empty())
395 st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
397 trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points[i].time_from_start;
399 if (trajectory.multi_dof_joint_trajectory.points.size() > i)
401 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
403 Eigen::Isometry3d
t =
tf2::transformToEigen(trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
404 st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j], t);
406 this_time_stamp = trajectory.multi_dof_joint_trajectory.header.stamp +
407 trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
411 last_time_stamp = this_time_stamp;
416 const moveit_msgs::RobotState& state,
417 const moveit_msgs::RobotTrajectory& trajectory)
437 double running_duration = 0.0;
438 for (; index < num_points; ++index)
441 if (running_duration >= duration)
444 before = std::max<int>(index - 1, 0);
445 after = std::min<int>(index, num_points - 1);
452 blend = (duration - before_time) / duration_from_previous_[index];
463 for (std::size_t i = 0; i <= index; ++i)
474 robot_state::RobotStatePtr& output_state)
const 480 int before = 0, after = 0;
Core components of MoveIt!
void swap(robot_trajectory::RobotTrajectory &other)
std::deque< robot_state::RobotStatePtr > waypoints_
geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d &T)
void setGroupName(const std::string &group_name)
const robot_model::JointModelGroup * group_
double getDuration() const
robot_model::RobotModelConstPtr robot_model_
RobotTrajectory(const robot_model::RobotModelConstPtr &robot_model, const std::string &group)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
geometry_msgs::TransformStamped t
std::size_t getWayPointCount() const
const std::string & getGroupName() const
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getName() const
Get the name of the joint group.
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...
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.
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::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints). ...
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indicies before and after a duration from start.
double getWaypointDurationFromStart(std::size_t index) const
Representation of a robot's state. This includes position, velocity, acceleration and effort...
void addSuffixWayPoint(const robot_state::RobotState &state, double dt)
Add a point to the trajectory.
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
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...
const double * getJointPositions(const std::string &joint_name) const
std::deque< double > duration_from_previous_
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)
double getAverageSegmentDuration() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
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...