|
| tl::expected< sensor_msgs::msg::JointState, std::string > | filterJointStateForGroup (const moveit_studio_agent_msgs::msg::RobotJointState &joint_state_in, const moveit_pro::base::RobotModelConstPtr &robot_model, const std::string &planning_group_name) |
| | Create a joint state that contains the subset of joints in an input joint state that are associated with a particular planning group.
|
| |
| moveit_msgs::msg::VisibilityConstraint | createCameraVisibilityConstraint (const std::string &camera_optical_frame, const std_msgs::msg::Header &target_header, const geometry_msgs::msg::Pose &target_pose, const double camera_field_of_view, const double target_diameter, const double sensor_z_offset) |
| | Create a VisibilityConstraint to make the robot look at an object in the scene.
|
| |
| std::string | getFullName (const moveit_pro::task_constructor::Stage *stage) |
| | Get the fully-qualified name of a MTC stage.
|
| |
| std::string | tfErrorGuidance (std::string_view tf_what) |
| | Classifies a TF2 exception's what() string and returns a short, subtype-specific hint with a link to the Transforms Troubleshooting docs page.
|
| |
| tl::expected< geometry_msgs::msg::TransformStamped, std::string > | getTransform (const tf2_ros::Buffer &buffer, const std::string &parent_frame_id, const std_msgs::msg::Header &child_frame_header, const std::chrono::duration< double > &timeout) |
| | Wraps a TF lookup within a tl::expected.
|
| |
| tl::expected< Eigen::Isometry3d, std::string > | getTransformAsIsometry (const tf2_ros::Buffer &buffer, const std::string &parent_frame_id, const std_msgs::msg::Header &child_frame_header, const std::chrono::duration< double > &timeout) |
| | Looks up a TF transform and returns it as an Eigen::Isometry3d.
|
| |
| std::string moveit_pro::helper_functions::tfErrorGuidance |
( |
std::string_view |
tf_what | ) |
|
|
inline |
Classifies a TF2 exception's what() string and returns a short, subtype-specific hint with a link to the Transforms Troubleshooting docs page.
The three extrapolation messages ("into the past", "into the future", "at time"), plus frame-missing and disconnected-tree variants, all have different root causes. Returning a one-line hint per subtype — instead of a monolithic "check system load" note — helps users reach the right remedy faster.
The classifier uses substring matching on the TF2 exception text because tf2_ros::Buffer::lookupTransform with a non-zero timeout may rethrow ExtrapolationException as a broader TransformException, so type-based dispatch is not reliable across the timeout vs. no-timeout code paths.