MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro::helper_functions Namespace Reference

Namespaces

namespace  tf_hints
 Hint phrases and docs-page anchors used by tfErrorGuidance.
 

Functions

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.
 

Function Documentation

◆ createCameraVisibilityConstraint()

moveit_msgs::msg::VisibilityConstraint moveit_pro::helper_functions::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 
)
inline

Create a VisibilityConstraint to make the robot look at an object in the scene.

Assumes that the sensor view direction is along the Z+ axis of the camera optical frame.

Parameters
camera_optical_frameFrame ID of the camera origin.
target_headerHeader containing the frame of reference and timestamp of the target object.
target_posePose of the center of the target object.
camera_field_of_viewAngular field of view of the camera, in radians. The constraint will keep the center of the target object within the field of view relative to the camera optical origin.
target_diameterDiameter of the target.
sensor_z_offsetDistance in front of the camera optical frame to place the visibility constraint cone.
Returns
The constraint with fields populated based on the input.

◆ filterJointStateForGroup()

tl::expected< sensor_msgs::msg::JointState, std::string > moveit_pro::helper_functions::filterJointStateForGroup ( const moveit_studio_agent_msgs::msg::RobotJointState &  joint_state_in,
const moveit_pro::base::RobotModelConstPtr &  robot_model,
const std::string &  planning_group_name 
)
inline

Create a joint state that contains the subset of joints in an input joint state that are associated with a particular planning group.

Parameters
joint_state_inInput joint state to filter
robot_modelRobot model defining which joints are part of which planning groups
planning_group_nameFilter to joints that are part of this planning group
Returns
A joint state containing names and joint positions for a subset of joints from joint_state_in which are part of the planning group named planning_group_name

◆ getFullName()

std::string moveit_pro::helper_functions::getFullName ( const moveit_pro::task_constructor::Stage *  stage)
inline

Get the fully-qualified name of a MTC stage.

The output from this function is intended to be used as the input for moveit_pro::task_constructor::ContainerBase::findChild().

Parameters
stagePointer to the stage
Returns
std::string Fully-qualified name composed of the name of the input stage appended to the names of each of its parent stages. The names are separated by a / character.

◆ getTransform()

tl::expected< geometry_msgs::msg::TransformStamped, std::string > moveit_pro::helper_functions::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 
)
inline

Wraps a TF lookup within a tl::expected.

Allows replacing tf2_ros::Buffer's default exception-based error handling with the expected-return concept. On failure, appends a subtype-specific hint and a link to the Transforms Troubleshooting docs page.

Parameters
bufferTF buffer to use for the lookup.
parent_frame_idFixed frame, used as parent frame in TF lookup
child_frame_headerHeader of the child frame. The lookup uses the timestamp from this header.
Returns
If successful, returns a stamped transform from the parent frame to the child frame. Returns an error message if the TF lookup fails.

◆ getTransformAsIsometry()

tl::expected< Eigen::Isometry3d, std::string > moveit_pro::helper_functions::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 
)
inline

Looks up a TF transform and returns it as an Eigen::Isometry3d.

Forwards to getTransform and converts the result via tf2::transformToEigen on success. On failure, produces the same enriched error message as getTransform (subtype-specific hint + link to the Transforms Troubleshooting docs page).

Parameters
bufferTF buffer to use for the lookup.
parent_frame_idFixed frame, used as parent frame in TF lookup.
child_frame_headerHeader of the child frame. The lookup uses the timestamp from this header.
timeoutDuration to wait for the transform to become available.
Returns
If successful, returns an Isometry3d from the parent frame to the child frame. Returns an error message if the TF lookup fails.

◆ tfErrorGuidance()

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.