38 #include <tf2/LinearMath/Quaternion.h>
39 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
40 #include <tf2_eigen/tf2_eigen.hpp>
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
45 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.trajectory_functions");
49 const std::string& group_name,
const std::string& link_name,
50 const Eigen::Isometry3d& pose,
const std::string&
frame_id,
51 const std::map<std::string, double>& seed,
52 std::map<std::string, double>& solution,
bool check_self_collision,
55 const moveit::core::RobotModelConstPtr& robot_model =
scene->getRobotModel();
56 if (!robot_model->hasJointModelGroup(group_name))
58 RCLCPP_ERROR_STREAM(LOGGER,
"Robot model has no planning group named as " << group_name);
62 if (
frame_id != robot_model->getModelFrame())
64 RCLCPP_ERROR_STREAM(LOGGER,
"Given frame (" <<
frame_id <<
") is unequal to model frame("
65 << robot_model->getModelFrame() <<
")");
70 rstate.setVariablePositions(seed);
73 if (check_self_collision)
77 const double* joint_group_variable_values) {
79 joint_group_variable_values);
85 if (rstate.setFromIK(jmg, pose, link_name, timeout, ik_constraint_function))
90 solution[joint_name] = rstate.getVariablePosition(joint_name);
96 RCLCPP_ERROR(LOGGER,
"Unable to find IK solution.");
104 const std::string& group_name,
const std::string& link_name,
105 const geometry_msgs::msg::Pose& pose,
const std::string&
frame_id,
106 const std::map<std::string, double>& seed,
107 std::map<std::string, double>& solution,
bool check_self_collision,
108 const double timeout)
110 Eigen::Isometry3d pose_eigen;
111 tf2::convert<geometry_msgs::msg::Pose, Eigen::Isometry3d>(pose, pose_eigen);
117 const std::map<std::string, double>& joint_state,
118 Eigen::Isometry3d& pose)
123 RCLCPP_ERROR_STREAM(LOGGER,
"The target link " << link_name <<
" is not known by robot.");
137 const std::map<std::string, double>& position_last,
const std::map<std::string, double>& velocity_last,
138 const std::map<std::string, double>& position_current,
double duration_last,
double duration_current,
141 const double epsilon = 10e-6;
142 if (duration_current <= epsilon)
144 RCLCPP_ERROR(LOGGER,
"Sample duration too small, cannot compute the velocity");
148 double velocity_current, acceleration_current;
150 for (
const auto& pos : position_current)
152 velocity_current = (pos.second - position_last.at(pos.first)) / duration_current;
154 if (!
joint_limits.verifyVelocityLimit(pos.first, velocity_current))
156 RCLCPP_ERROR_STREAM(LOGGER,
"Joint velocity limit of "
157 << pos.first <<
" violated. Set the velocity scaling factor lower!"
158 <<
" Actual joint velocity is " << velocity_current <<
", while the limit is "
159 <<
joint_limits.getLimit(pos.first).max_velocity <<
". ");
163 acceleration_current = (velocity_current - velocity_last.at(pos.first)) / (duration_last + duration_current) * 2;
165 if (fabs(velocity_last.at(pos.first)) <= fabs(velocity_current))
167 if (
joint_limits.getLimit(pos.first).has_acceleration_limits &&
168 fabs(acceleration_current) > fabs(
joint_limits.getLimit(pos.first).max_acceleration))
170 RCLCPP_ERROR_STREAM(LOGGER,
"Joint acceleration limit of "
171 << pos.first <<
" violated. Set the acceleration scaling factor lower!"
172 <<
" Actual joint acceleration is " << acceleration_current
173 <<
", while the limit is " <<
joint_limits.getLimit(pos.first).max_acceleration
181 if (
joint_limits.getLimit(pos.first).has_deceleration_limits &&
182 fabs(acceleration_current) > fabs(
joint_limits.getLimit(pos.first).max_deceleration))
184 RCLCPP_ERROR_STREAM(LOGGER,
"Joint deceleration limit of "
185 << pos.first <<
" violated. Set the acceleration scaling factor lower!"
186 <<
" Actual joint deceleration is " << acceleration_current
187 <<
", while the limit is " <<
joint_limits.getLimit(pos.first).max_deceleration
198 const planning_scene::PlanningSceneConstPtr&
scene,
200 const std::string& group_name,
const std::string& link_name,
201 const std::map<std::string, double>& initial_joint_position,
const double& sampling_time,
202 trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
203 bool check_self_collision)
205 RCLCPP_DEBUG(LOGGER,
"Generate joint trajectory from a Cartesian trajectory.");
207 const moveit::core::RobotModelConstPtr& robot_model =
scene->getRobotModel();
209 rclcpp::Time generation_begin = clock.now();
212 const double epsilon = 10e-06;
213 std::vector<double> time_samples;
214 for (
double t_sample = 0.0; t_sample < trajectory.Duration() - epsilon; t_sample += sampling_time)
216 time_samples.push_back(t_sample);
218 time_samples.push_back(trajectory.Duration());
221 Eigen::Isometry3d pose_sample;
222 std::map<std::string, double> ik_solution_last, ik_solution, joint_velocity_last;
223 ik_solution_last = initial_joint_position;
224 for (
const auto& item : ik_solution_last)
226 joint_velocity_last[item.first] = 0.0;
229 for (std::vector<double>::const_iterator time_iter = time_samples.begin(); time_iter != time_samples.end();
232 tf2::transformKDLToEigen(trajectory.Pos(*time_iter), pose_sample);
234 if (!
computePoseIK(
scene, group_name, link_name, pose_sample, robot_model->getModelFrame(), ik_solution_last,
235 ik_solution, check_self_collision))
237 RCLCPP_ERROR(LOGGER,
"Failed to compute inverse kinematics solution for sampled Cartesian pose.");
238 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
239 joint_trajectory.points.clear();
244 double duration_current_sample = sampling_time;
246 if (time_iter == (time_samples.end() - 1) && time_samples.size() > 1)
248 duration_current_sample = *time_iter - *(time_iter - 1);
250 if (time_samples.size() == 1)
252 duration_current_sample = *time_iter;
256 if (time_iter != time_samples.begin() &&
260 RCLCPP_ERROR_STREAM(LOGGER,
"Inverse kinematics solution at "
262 <<
"s violates the joint velocity/acceleration/deceleration limits.");
263 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
264 joint_trajectory.points.clear();
269 trajectory_msgs::msg::JointTrajectoryPoint point;
272 joint_trajectory.joint_names.clear();
273 for (
const auto& start_joint : initial_joint_position)
275 joint_trajectory.joint_names.push_back(start_joint.first);
278 point.time_from_start = rclcpp::Duration::from_seconds(*time_iter);
279 for (
const auto& joint_name : joint_trajectory.joint_names)
281 point.positions.push_back(ik_solution.at(joint_name));
283 if (time_iter != time_samples.begin() && time_iter != time_samples.end() - 1)
285 double joint_velocity =
286 (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current_sample;
287 point.velocities.push_back(joint_velocity);
288 point.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
289 (duration_current_sample + sampling_time) * 2);
290 joint_velocity_last[joint_name] = joint_velocity;
294 point.velocities.push_back(0.);
295 point.accelerations.push_back(0.);
296 joint_velocity_last[joint_name] = 0.;
301 joint_trajectory.points.push_back(point);
302 ik_solution_last = ik_solution;
305 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
306 double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
307 RCLCPP_DEBUG_STREAM(LOGGER,
"Generate trajectory (N-Points: "
308 << joint_trajectory.points.size() <<
") took " << duration_ms <<
" ms | "
309 << duration_ms / joint_trajectory.points.size() <<
" ms per Point");
315 const planning_scene::PlanningSceneConstPtr&
scene,
318 const std::string& link_name,
const std::map<std::string, double>& initial_joint_position,
319 const std::map<std::string, double>& initial_joint_velocity,
320 trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
321 bool check_self_collision)
323 RCLCPP_DEBUG(LOGGER,
"Generate joint trajectory from a Cartesian trajectory.");
325 const moveit::core::RobotModelConstPtr& robot_model =
scene->getRobotModel();
327 rclcpp::Time generation_begin = clock.now();
329 std::map<std::string, double> ik_solution_last = initial_joint_position;
330 std::map<std::string, double> joint_velocity_last = initial_joint_velocity;
331 double duration_last = 0;
332 double duration_current = 0;
333 joint_trajectory.joint_names.clear();
334 for (
const auto& joint_position : ik_solution_last)
336 joint_trajectory.joint_names.push_back(joint_position.first);
338 std::map<std::string, double> ik_solution;
339 for (
size_t i = 0; i < trajectory.
points.size(); ++i)
343 ik_solution_last, ik_solution, check_self_collision))
345 RCLCPP_ERROR(LOGGER,
"Failed to compute inverse kinematics solution for sampled "
347 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
348 joint_trajectory.points.clear();
355 duration_current = trajectory.
points.front().time_from_start.seconds();
356 duration_last = duration_current;
361 trajectory.
points.at(i).time_from_start.seconds() - trajectory.
points.at(i - 1).time_from_start.seconds();
364 if (!
verifySampleJointLimits(ik_solution_last, joint_velocity_last, ik_solution, duration_last, duration_current,
371 RCLCPP_ERROR_STREAM(LOGGER,
"Inverse kinematics solution of the "
373 <<
"th sample violates the joint "
374 "velocity/acceleration/deceleration limits.");
375 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
376 joint_trajectory.points.clear();
382 trajectory_msgs::msg::JointTrajectoryPoint waypoint_joint;
383 waypoint_joint.time_from_start = trajectory.
points.at(i).time_from_start;
384 for (
const auto& joint_name : joint_trajectory.joint_names)
386 waypoint_joint.positions.push_back(ik_solution.at(joint_name));
387 double joint_velocity = (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current;
388 waypoint_joint.velocities.push_back(joint_velocity);
389 waypoint_joint.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
390 (duration_current + duration_last) * 2);
392 joint_velocity_last[joint_name] = joint_velocity;
396 joint_trajectory.points.push_back(waypoint_joint);
397 ik_solution_last = ik_solution;
398 duration_last = duration_current;
401 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
403 double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
404 RCLCPP_DEBUG_STREAM(LOGGER,
"Generate trajectory (N-Points: "
405 << joint_trajectory.points.size() <<
") took " << duration_ms <<
" ms | "
406 << duration_ms / joint_trajectory.points.size() <<
" ms per Point");
412 const robot_trajectory::RobotTrajectoryPtr& first_trajectory,
413 const robot_trajectory::RobotTrajectoryPtr& second_trajectory,
double epsilon,
double& sampling_time)
417 std::size_t n1 = first_trajectory->getWayPointCount() - 1;
418 std::size_t n2 = second_trajectory->getWayPointCount() - 1;
419 if ((n1 < 2) && (n2 < 2))
421 RCLCPP_ERROR_STREAM(LOGGER,
"Both trajectories do not have enough points to determine sampling time.");
427 sampling_time = first_trajectory->getWayPointDurationFromPrevious(1);
431 sampling_time = second_trajectory->getWayPointDurationFromPrevious(1);
434 for (std::size_t i = 1; i < std::max(n1, n2); ++i)
438 if (fabs(sampling_time - first_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
440 RCLCPP_ERROR_STREAM(LOGGER,
"First trajectory violates sampline time " << sampling_time <<
" between points "
441 << (i - 1) <<
"and " << i
449 if (fabs(sampling_time - second_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
451 RCLCPP_ERROR_STREAM(LOGGER,
"Second trajectory violates sampline time " << sampling_time <<
" between points "
452 << (i - 1) <<
"and " << i
464 const std::string& joint_group_name,
double epsilon)
466 Eigen::VectorXd joint_position_1, joint_position_2;
471 if ((joint_position_1 - joint_position_2).norm() > epsilon)
473 RCLCPP_DEBUG_STREAM(LOGGER,
"Joint positions of the two states are different. state1: "
474 << joint_position_1 <<
" state2: " << joint_position_2);
478 Eigen::VectorXd joint_velocity_1, joint_velocity_2;
483 if ((joint_velocity_1 - joint_velocity_2).norm() > epsilon)
485 RCLCPP_DEBUG_STREAM(LOGGER,
"Joint velocities of the two states are different. state1: "
486 << joint_velocity_1 <<
" state2: " << joint_velocity_2);
490 Eigen::VectorXd joint_acc_1, joint_acc_2;
495 if ((joint_acc_1 - joint_acc_2).norm() > epsilon)
497 RCLCPP_DEBUG_STREAM(LOGGER,
"Joint accelerations of the two states are different. state1: "
498 << joint_acc_1 <<
" state2: " << joint_acc_2);
508 Eigen::VectorXd joint_variable;
510 if (joint_variable.norm() >
EPSILON)
512 RCLCPP_DEBUG(LOGGER,
"Joint velocities are not zero.");
516 if (joint_variable.norm() >
EPSILON)
518 RCLCPP_DEBUG(LOGGER,
"Joint accelerations are not zero.");
527 const robot_trajectory::RobotTrajectoryPtr& traj,
528 bool inverseOrder, std::size_t& index)
530 RCLCPP_DEBUG(LOGGER,
"Start linear search for intersection point.");
532 const size_t waypoint_num = traj->getWayPointCount();
536 for (
size_t i = waypoint_num - 1; i > 0; --i)
538 if (
intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
539 traj->getWayPointPtr(i - 1)->getFrameTransform(link_name).translation(),
r))
548 for (
size_t i = 0; i < waypoint_num - 1; ++i)
550 if (
intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
551 traj->getWayPointPtr(i + 1)->getFrameTransform(link_name).translation(),
r))
566 return ((p_current - p_center).norm() <=
r) && ((p_next - p_center).norm() >=
r);
572 const double*
const ik_solution)
580 scene->checkSelfCollision(collision_req, collision_res, *rstate);
587 tf2::convert<geometry_msgs::msg::Quaternion, tf2::Quaternion>(quat, q);
588 quat = tf2::toMsg(q.normalized());
592 const geometry_msgs::msg::Quaternion& orientation,
593 const geometry_msgs::msg::Vector3& offset)
595 Eigen::Quaterniond quat;
596 tf2::fromMsg(orientation, quat);
599 tf2::fromMsg(position, v);
601 Eigen::Isometry3d pose = Eigen::Translation3d(v) * quat;
603 tf2::fromMsg(offset, v);
604 pose.translation() -= quat * v;
610 return getConstraintPose(goal.position_constraints.front().constraint_region.primitive_poses.front().position,
611 goal.orientation_constraints.front().orientation,
612 goal.position_constraints.front().target_point_offset);
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
Vec3fX< details::Vec3Data< double > > Vector3d
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, const double &sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool linearSearchIntersectionPoint(const std::string &link_name, const Eigen::Vector3d ¢er_position, const double &r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
Performs a linear search for the intersection point of the trajectory with the blending radius.
bool isStateColliding(const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
Checks if current robot state is in self collision.
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool verifySampleJointLimits(const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
verify the velocity/acceleration limits of current sample (based on backward difference computation) ...
bool intersectionFound(const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, const double &r)
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
const rclcpp::Logger LOGGER
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
std::vector< CartesianTrajectoryPoint > points
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)
Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point &position, const geometry_msgs::msg::Quaternion &orientation, const geometry_msgs::msg::Vector3 &offset)
Adapt goal pose, defined by position+orientation, to consider offset.