MoveIt Pro Behavior Interface
5.2.0
Library for developing custom behaviors for use in MoveIt Pro
|
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 moveit_studio_agent_msgs::msg::RobotJointState &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... | |
|
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.
camera_optical_frame | Frame ID of the camera origin. |
target_header | Header containing the frame of reference and timestamp of the target object. |
target_pose | Pose of the center of the target object. |
camera_field_of_view | Angular 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_diameter | Diameter of the target. |
sensor_z_offset | Distance in front of the camera optical frame to place the visibility constraint cone. |
|
inline |
Create a joint state that contains the subset of joints in an input joint state that are associated with a particular planning group.
joint_state_in | Input joint state to filter |
robot_model | Robot model defining which joints are part of which planning groups |
planning_group_name | Filter to joints that are part of this planning group |
|
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.
controller_names | Input space-separated list of controller names. For example, "/controller1 /controller2". |
controller_names. |
|
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().
stage | Pointer to the stage |
/
character.
|
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.
buffer | TF buffer to use for the lookup. |
parent_frame_id | Fixed frame, used as parent frame in TF lookup |
child_frame_header | Header of the child frame. The lookup uses the timestamp from this header. |