MoveIt Pro Behavior Interface  5.0.1
Library for developing custom behaviors for use in MoveIt Pro
moveit_studio::helper_functions Namespace Reference

Functions

std::optional< moveit::task_constructor::TrajectoryExecutionInfo > getDefaultTrajectoryExecutionInfo (const std::string &controller_names)
 Process a string containing a space-separated list of controller names to compose an MTC TrajectoryExecutionInfo object describing which controllers to use when executing the trajectory. More...
 
tl::expected< sensor_msgs::msg::JointState, std::string > filterJointStateForGroup (const sensor_msgs::msg::JointState &joint_state_in, const moveit::core::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. More...
 
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. More...
 
std::string getFullName (const moveit::task_constructor::Stage *stage)
 Get the fully-qualified name of a MTC stage. More...
 
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. More...
 

Function Documentation

◆ createCameraVisibilityConstraint()

moveit_msgs::msg::VisibilityConstraint moveit_studio::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_studio::helper_functions::filterJointStateForGroup ( const sensor_msgs::msg::JointState &  joint_state_in,
const moveit::core::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

◆ getDefaultTrajectoryExecutionInfo()

std::optional<moveit::task_constructor::TrajectoryExecutionInfo> moveit_studio::helper_functions::getDefaultTrajectoryExecutionInfo ( const std::string &  controller_names)
inline

Process a string containing a space-separated list of controller names to compose an MTC TrajectoryExecutionInfo object describing which controllers to use when executing the trajectory.

Parameters
controller_namesInput space-separated list of controller names. For example, "/controller1 /controller2".
Returns
An optional wrapping the output TrajectoryExecutionInfo. Set to nullopt if an exception was caught while parsing
Parameters
controller_names.

◆ getFullName()

std::string moveit_studio::helper_functions::getFullName ( const moveit::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::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_studio::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.

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.