Creates a CollisionObject from a SolidPrimitive, pose, and object ID.
More...
#include <create_collision_object_from_solid_primitive.hpp>
Creates a CollisionObject from a SolidPrimitive, pose, and object ID.
| Data Port Name | Port Type | Object Type |
| solid_primitive | input | shape_msgs::msg::SolidPrimitive |
| pose | input | geometry_msgs::msg::PoseStamped |
| object_id | input | std::string |
| collision_object | output | moveit_msgs::msg::CollisionObject |
◆ CreateCollisionObjectFromSolidPrimitive()
| moveit_studio::behaviors::CreateCollisionObjectFromSolidPrimitive::CreateCollisionObjectFromSolidPrimitive |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
| BT::KeyValueVector moveit_studio::behaviors::CreateCollisionObjectFromSolidPrimitive::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
| BT::PortsList moveit_studio::behaviors::CreateCollisionObjectFromSolidPrimitive::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
| BT::NodeStatus moveit_studio::behaviors::CreateCollisionObjectFromSolidPrimitive::tick |
( |
| ) |
|
|
override |
The documentation for this class was generated from the following files: