96MoveItErrorCode
restateInNewFrame(
const std::shared_ptr<tf2_ros::Buffer>& tf,
const std::string& target_frame,
97 const std::string& source_frame, geometry_msgs::msg::Point* translation,
98 geometry_msgs::msg::Quaternion* rotation,
const tf2::TimePoint& lookup_time)
100 if (target_frame == source_frame)
102 return MoveItErrorCode::SUCCESS;
104 if (translation ==
nullptr && rotation ==
nullptr)
106 return MoveItErrorCode::SUCCESS;
110 geometry_msgs::msg::TransformStamped transform;
113 transform = tf->lookupTransform(target_frame, source_frame, lookup_time);
115 catch (tf2::TransformException& ex)
117 std::stringstream ss;
118 ss <<
"Could not get transform for " << source_frame <<
" to " << target_frame <<
": " << ex.what();
123 if (translation !=
nullptr)
125 translation->x += transform.transform.translation.x;
126 translation->y += transform.transform.translation.y;
127 translation->z += transform.transform.translation.z;
131 if (rotation !=
nullptr)
133 tf2::Quaternion input_quat(rotation->x, rotation->y, rotation->z, rotation->w);
134 tf2::Quaternion transform_quat(transform.transform.rotation.x, transform.transform.rotation.y,
135 transform.transform.rotation.z, transform.transform.rotation.w);
137 input_quat.normalize();
138 transform_quat.normalize();
140 auto final_quat = input_quat * transform_quat;
141 final_quat.normalize();
143 rotation->x = final_quat.getX();
144 rotation->y = final_quat.getY();
145 rotation->z = final_quat.getZ();
146 rotation->w = final_quat.getW();
149 return moveit::core::MoveItErrorCode::SUCCESS;
221 const MoveGroupInterface&
move_group,
double match_tolerance,
222 const std::string& reference_frame_id,
const std::string& prefix)
224 const std::shared_ptr<tf2_ros::Buffer> tf_buffer =
move_group.getTF();
228 bool emit_position_constraint_warning =
false;
229 for (
const auto& constraint : constraints)
231 for (
const auto& position_constraint : constraint.position_constraints)
233 if (!position_constraint.constraint_region.primitives.empty())
235 emit_position_constraint_warning =
true;
239 if (emit_position_constraint_warning)
244 if (emit_position_constraint_warning)
246 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".position_constraints.constraint_region: Not supported.");
249 bool emit_visibility_constraint_warning =
false;
250 for (
const auto& constraint : constraints)
252 if (!constraint.visibility_constraints.empty())
254 emit_visibility_constraint_warning =
true;
258 if (emit_visibility_constraint_warning)
260 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".visibility_constraints: Not supported.");
265 size_t constraint_idx = 0;
266 for (
auto& constraint : constraints)
273 std::string constraint_prefix = prefix +
"_" + std::to_string(constraint_idx++);
276 size_t joint_idx = 0;
277 for (
const auto& joint_constraint : constraint.joint_constraints)
279 std::string query_name = constraint_prefix +
".joint_constraints_" + std::to_string(joint_idx++);
280 query.append(query_name +
".joint_name", joint_constraint.joint_name);
282 query.appendGTE(query_name +
".tolerance_above", joint_constraint.tolerance_above);
283 query.appendLTE(query_name +
".tolerance_below", joint_constraint.tolerance_below);
287 if (!constraint.position_constraints.empty())
290 query.append(constraint_prefix +
".position_constraints.header.frame_id", reference_frame_id);
292 size_t position_idx = 0;
293 for (
const auto& position_constraint : constraint.position_constraints)
295 std::string query_name = constraint_prefix +
".position_constraints_" + std::to_string(position_idx++);
297 geometry_msgs::msg::Point canonical_position;
298 canonical_position.x = position_constraint.target_point_offset.x;
299 canonical_position.y = position_constraint.target_point_offset.y;
300 canonical_position.z = position_constraint.target_point_offset.z;
303 if (position_constraint.header.frame_id != reference_frame_id)
305 if (MoveItErrorCode status =
307 &canonical_position,
nullptr, tf2::TimePointZero);
308 status != MoveItErrorCode::SUCCESS)
313 std::stringstream ss;
314 ss <<
"Skipping " << prefix <<
":" << query_name <<
" query append: " << status.message;
315 return MoveItErrorCode(status.val, status.message);
319 query.append(query_name +
".link_name", position_constraint.link_name);
330 if (!constraint.orientation_constraints.empty())
333 query.append(constraint_prefix +
".orientation_constraints.header.frame_id", reference_frame_id);
336 for (
const auto& orientation_constraint : constraint.orientation_constraints)
338 std::string query_name = constraint_prefix +
".orientation_constraints_" + std::to_string(ori_idx++);
339 geometry_msgs::msg::Quaternion canonical_orientation = orientation_constraint.orientation;
342 if (orientation_constraint.header.frame_id != reference_frame_id)
344 if (MoveItErrorCode status =
346 nullptr, &canonical_orientation, tf2::TimePointZero);
347 status != MoveItErrorCode::SUCCESS)
352 std::stringstream ss;
353 ss <<
"Skipping " << prefix <<
":" << query_name <<
" query append: " << status.message;
354 return MoveItErrorCode(status.val, status.message);
358 query.append(query_name +
".link_name", orientation_constraint.link_name);
367 return moveit::core::MoveItErrorCode::SUCCESS;
371 std::vector<moveit_msgs::msg::Constraints> constraints,
373 const std::string& workspace_frame_id,
374 const std::string& prefix)
376 const std::shared_ptr<tf2_ros::Buffer> tf_buffer =
move_group.getTF();
380 bool emit_position_constraint_warning =
false;
381 for (
const auto& constraint : constraints)
383 for (
const auto& position_constraint : constraint.position_constraints)
385 if (!position_constraint.constraint_region.primitives.empty())
387 emit_position_constraint_warning =
true;
391 if (emit_position_constraint_warning)
396 if (emit_position_constraint_warning)
398 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".position_constraints.constraint_region: Not supported.");
401 bool emit_visibility_constraint_warning =
false;
402 for (
const auto& constraint : constraints)
404 if (!constraint.visibility_constraints.empty())
406 emit_visibility_constraint_warning =
true;
410 if (emit_visibility_constraint_warning)
412 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".visibility_constraints: Not supported.");
417 size_t constraint_idx = 0;
418 for (
auto& constraint : constraints)
425 std::string constraint_prefix = prefix +
"_" + std::to_string(constraint_idx++);
428 size_t joint_idx = 0;
429 for (
const auto& joint_constraint : constraint.joint_constraints)
431 std::string meta_name = constraint_prefix +
".joint_constraints_" + std::to_string(joint_idx++);
432 metadata.append(meta_name +
".joint_name", joint_constraint.joint_name);
433 metadata.append(meta_name +
".position", joint_constraint.position);
434 metadata.append(meta_name +
".tolerance_above", joint_constraint.tolerance_above);
435 metadata.append(meta_name +
".tolerance_below", joint_constraint.tolerance_below);
439 if (!constraint.position_constraints.empty())
442 metadata.append(constraint_prefix +
".position_constraints.header.frame_id", workspace_frame_id);
444 size_t position_idx = 0;
445 for (
const auto& position_constraint : constraint.position_constraints)
447 std::string meta_name = constraint_prefix +
".position_constraints_" + std::to_string(position_idx++);
449 geometry_msgs::msg::Point canonical_position;
450 canonical_position.x = position_constraint.target_point_offset.x;
451 canonical_position.y = position_constraint.target_point_offset.y;
452 canonical_position.z = position_constraint.target_point_offset.z;
455 if (position_constraint.header.frame_id != workspace_frame_id)
457 if (MoveItErrorCode status =
459 &canonical_position,
nullptr, tf2::TimePointZero);
460 status != MoveItErrorCode::SUCCESS)
465 std::stringstream ss;
466 ss <<
"Skipping " << prefix <<
":" << meta_name <<
" metadata append: " << status.message;
467 return MoveItErrorCode(status.val, status.message);
471 metadata.append(meta_name +
".link_name", position_constraint.link_name);
472 metadata.append(meta_name +
".target_point_offset.x", canonical_position.x);
473 metadata.append(meta_name +
".target_point_offset.y", canonical_position.y);
474 metadata.append(meta_name +
".target_point_offset.z", canonical_position.z);
479 if (!constraint.orientation_constraints.empty())
482 metadata.append(constraint_prefix +
".orientation_constraints.header.frame_id", workspace_frame_id);
485 for (
const auto& orientation_constraint : constraint.orientation_constraints)
487 std::string meta_name = constraint_prefix +
".orientation_constraints_" + std::to_string(ori_idx++);
488 geometry_msgs::msg::Quaternion canonical_orientation = orientation_constraint.orientation;
491 if (orientation_constraint.header.frame_id != workspace_frame_id)
493 if (MoveItErrorCode status =
495 nullptr, &canonical_orientation, tf2::TimePointZero);
496 status != MoveItErrorCode::SUCCESS)
501 std::stringstream ss;
502 ss <<
"Skipping " << prefix <<
":" << meta_name <<
" metadata append: " << status.message;
503 return MoveItErrorCode(status.val, status.message);
507 metadata.append(meta_name +
".link_name", orientation_constraint.link_name);
508 metadata.append(meta_name +
".orientation.x", canonical_orientation.x);
509 metadata.append(meta_name +
".orientation.y", canonical_orientation.y);
510 metadata.append(meta_name +
".orientation.z", canonical_orientation.z);
511 metadata.append(meta_name +
".orientation.w", canonical_orientation.w);
516 return moveit::core::MoveItErrorCode::SUCCESS;
523 const MoveGroupInterface&
move_group,
double match_tolerance,
524 const std::string& prefix)
528 if (!robot_state.multi_dof_joint_state.joint_names.empty())
530 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".multi_dof_joint_states: Not supported.");
532 if (!robot_state.attached_collision_objects.empty())
534 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".attached_collision_objects: Not supported.");
539 if (robot_state.is_diff)
555 moveit::core::RobotStatePtr current_state =
move_group.getCurrentState();
561 std::stringstream ss;
562 ss <<
"Skipping " << prefix <<
" query append: "
563 <<
"Could not get robot state.";
564 return MoveItErrorCode(MoveItErrorCode::UNABLE_TO_AQUIRE_SENSOR_DATA, ss.str());
567 moveit_msgs::msg::RobotState current_state_msg;
568 robotStateToRobotStateMsg(*current_state, current_state_msg);
570 for (
size_t i = 0; i < current_state_msg.joint_state.name.size(); ++i)
572 query.append(prefix +
".joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i));
574 current_state_msg.joint_state.position.at(i), match_tolerance);
579 for (
size_t i = 0; i < robot_state.joint_state.name.size(); ++i)
581 query.append(prefix +
".joint_state.name_" + std::to_string(i), robot_state.joint_state.name.at(i));
583 robot_state.joint_state.position.at(i), match_tolerance);
587 return moveit::core::MoveItErrorCode::SUCCESS;
592 const MoveGroupInterface&
move_group,
const std::string& prefix)
596 if (!robot_state.multi_dof_joint_state.joint_names.empty())
598 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".multi_dof_joint_states: Not supported.");
600 if (!robot_state.attached_collision_objects.empty())
602 RCLCPP_WARN_STREAM(getLogger(),
"Ignoring " << prefix <<
".attached_collision_objects: Not supported.");
607 if (robot_state.is_diff)
623 moveit::core::RobotStatePtr current_state =
move_group.getCurrentState();
629 std::stringstream ss;
630 ss <<
"Skipping " << prefix <<
" metadata append: "
631 <<
"Could not get robot state.";
632 return MoveItErrorCode(MoveItErrorCode::UNABLE_TO_AQUIRE_SENSOR_DATA, ss.str());
635 moveit_msgs::msg::RobotState current_state_msg;
636 robotStateToRobotStateMsg(*current_state, current_state_msg);
638 for (
size_t i = 0; i < current_state_msg.joint_state.name.size(); ++i)
640 metadata.append(prefix +
".joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i));
641 metadata.append(prefix +
".joint_state.position_" + std::to_string(i),
642 current_state_msg.joint_state.position.at(i));
647 for (
size_t i = 0; i < robot_state.joint_state.name.size(); ++i)
649 metadata.append(prefix +
".joint_state.name_" + std::to_string(i), robot_state.joint_state.name.at(i));
650 metadata.append(prefix +
".joint_state.position_" + std::to_string(i), robot_state.joint_state.position.at(i));
654 return moveit::core::MoveItErrorCode::SUCCESS;