41 #include <geometric_shapes/check_isometry.h>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
53 static const std::size_t MIN_STEPS_FOR_JUMP_THRESH = 10;
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_robot_state.cartesian_interpolator");
58 RobotState* start_state,
const JointModelGroup*
group, std::vector<RobotStatePtr>& traj,
const LinkModel* link,
59 const Eigen::Vector3d& translation,
bool global_reference_frame,
const MaxEEFStep& max_step,
63 const double distance = translation.norm();
65 Eigen::Isometry3d pose = start_state->getGlobalLinkTransform(link);
68 pose.translation() += global_reference_frame ? translation : pose.linear() * translation;
72 max_step, jump_threshold, validCallback,
77 RobotState* start_state,
const JointModelGroup*
group, std::vector<RobotStatePtr>& traj,
const LinkModel* link,
78 const Eigen::Isometry3d& target,
bool global_reference_frame,
const MaxEEFStep& max_step,
81 const Eigen::Isometry3d& link_offset)
84 ASSERT_ISOMETRY(target)
85 ASSERT_ISOMETRY(link_offset)
87 const std::vector<const JointModel*>& cjnt =
group->getContinuousJointModels();
89 for (
const JointModel* joint : cjnt)
90 start_state->enforceBounds(joint);
93 Eigen::Isometry3d start_pose = start_state->getGlobalLinkTransform(link) * link_offset;
94 Eigen::Isometry3d offset = link_offset.inverse();
97 Eigen::Isometry3d rotated_target = global_reference_frame ? target : start_pose * target;
99 Eigen::Quaterniond start_quaternion(start_pose.linear());
100 Eigen::Quaterniond target_quaternion(rotated_target.linear());
102 if (max_step.translation <= 0.0 && max_step.rotation <= 0.0)
104 RCLCPP_ERROR(LOGGER,
"Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and "
105 "MaxEEFStep.translation components must be non-negative and at least one component must be "
106 "greater than zero");
110 double rotation_distance = start_quaternion.angularDistance(target_quaternion);
111 double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
114 std::size_t translation_steps = 0;
115 if (max_step.translation > 0.0)
116 translation_steps = floor(translation_distance / max_step.translation);
118 std::size_t rotation_steps = 0;
119 if (max_step.rotation > 0.0)
120 rotation_steps = floor(rotation_distance / max_step.rotation);
123 std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
124 if (jump_threshold.factor > 0 && steps < MIN_STEPS_FOR_JUMP_THRESH)
125 steps = MIN_STEPS_FOR_JUMP_THRESH;
128 std::vector<double> consistency_limits;
129 if (jump_threshold.prismatic > 0 || jump_threshold.revolute > 0)
130 for (
const JointModel* jm :
group->getActiveJointModels())
133 switch (jm->getType())
136 limit = jump_threshold.revolute;
139 limit = jump_threshold.prismatic;
145 limit = jm->getMaximumExtent();
146 consistency_limits.push_back(limit);
150 traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
152 double last_valid_percentage = 0.0;
153 for (std::size_t i = 1; i <= steps; ++i)
155 double percentage = (double)i / (
double)steps;
157 Eigen::Isometry3d pose(start_quaternion.slerp(percentage, target_quaternion));
158 pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
162 if (start_state->setFromIK(
group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback,
options,
164 traj.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
168 last_valid_percentage = percentage;
173 return CartesianInterpolator::Percentage(last_valid_percentage);
177 RobotState* start_state,
const JointModelGroup*
group, std::vector<RobotStatePtr>& traj,
const LinkModel* link,
178 const EigenSTL::vector_Isometry3d&
waypoints,
bool global_reference_frame,
const MaxEEFStep& max_step,
181 const Eigen::Isometry3d& link_offset)
183 double percentage_solved = 0.0;
184 for (std::size_t i = 0; i <
waypoints.size(); ++i)
187 static const JumpThreshold NO_JOINT_SPACE_JUMP_TEST;
188 std::vector<RobotStatePtr> waypoint_traj;
189 double wp_percentage_solved =
191 NO_JOINT_SPACE_JUMP_TEST, validCallback,
options, cost_function, link_offset);
192 if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
194 percentage_solved = (double)(i + 1) / (double)
waypoints.size();
195 std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
196 if (i > 0 && !waypoint_traj.empty())
197 std::advance(start, 1);
198 traj.insert(traj.end(), start, waypoint_traj.end());
202 percentage_solved += wp_percentage_solved / (double)
waypoints.size();
203 std::vector<RobotStatePtr>::iterator start = waypoint_traj.begin();
204 if (i > 0 && !waypoint_traj.empty())
205 std::advance(start, 1);
206 traj.insert(traj.end(), start, waypoint_traj.end());
213 return CartesianInterpolator::Percentage(percentage_solved);
217 std::vector<RobotStatePtr>& traj,
220 double percentage_solved = 1.0;
221 if (traj.size() <= 1)
222 return percentage_solved;
224 if (jump_threshold.
factor > 0.0)
234 std::vector<RobotStatePtr>& traj,
235 double jump_threshold_factor)
237 if (traj.size() < MIN_STEPS_FOR_JUMP_THRESH)
240 "The computed trajectory is too short to detect jumps in joint-space "
241 "Need at least %zu steps, only got %zu. Try a lower max_step.",
242 MIN_STEPS_FOR_JUMP_THRESH, traj.size());
245 std::vector<double> dist_vector;
246 dist_vector.reserve(traj.size() - 1);
247 double total_dist = 0.0;
248 for (std::size_t i = 1; i < traj.size(); ++i)
250 double dist_prev_point = traj[i]->distance(*traj[i - 1],
group);
251 dist_vector.push_back(dist_prev_point);
252 total_dist += dist_prev_point;
255 double percentage = 1.0;
257 double thres = jump_threshold_factor * (total_dist / (double)dist_vector.size());
258 for (std::size_t i = 0; i < dist_vector.size(); ++i)
259 if (dist_vector[i] > thres)
261 RCLCPP_DEBUG(LOGGER,
"Truncating Cartesian path due to detected jump in joint-space distance");
262 percentage = (double)(i + 1) / (double)(traj.size());
271 std::vector<RobotStatePtr>& traj,
272 double revolute_threshold,
273 double prismatic_threshold)
275 bool check_revolute = revolute_threshold > 0.0;
276 bool check_prismatic = prismatic_threshold > 0.0;
278 double joint_threshold;
280 bool still_valid =
true;
281 const std::vector<const JointModel*>& joints =
group->getActiveJointModels();
282 for (std::size_t traj_ix = 0, ix_end = traj.size() - 1; traj_ix != ix_end; ++traj_ix)
284 for (
auto& joint : joints)
286 switch (joint->getType())
289 check_joint = check_revolute;
290 joint_threshold = revolute_threshold;
293 check_joint = check_prismatic;
294 joint_threshold = prismatic_threshold;
298 "Joint %s has not supported type %s. \n"
299 "checkAbsoluteJointSpaceJump only supports prismatic and revolute joints.",
300 joint->getName().c_str(), joint->getTypeName().c_str());
305 double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
308 RCLCPP_DEBUG(LOGGER,
"Truncating Cartesian path due to detected jump of %.4f > %.4f in joint %s",
distance,
309 joint_threshold, joint->getName().c_str());
318 double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
319 traj.resize(traj_ix + 1);
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
static Percentage checkAbsoluteJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double revolute_jump_threshold, double prismatic_jump_threshold)
Tests for absolute joint space jumps of the trajectory traj.
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
static Percentage checkRelativeJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double jump_threshold_factor)
Tests for relative joint space jumps of the trajectory traj.
static Percentage checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const JumpThreshold &jump_threshold)
Tests joint space jumps of a trajectory.
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_...
Main namespace for MoveIt.
double distance(const urdf::Pose &transform)
A set of options for the kinematics solver.
Struct for containing jump_threshold.