|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Publishes a visualization marker showing a camera frustum as a LINE_LIST. More...
#include <visualize_camera_frustum.hpp>


Public Member Functions | |
| VisualizeCameraFrustum (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| BT::NodeStatus | tick () override |
Public Member Functions inherited from moveit_pro::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Static Public Attributes | |
| static constexpr auto | kPortIDCameraPose = "camera_pose" |
| static constexpr auto | kPortIDNearPlane = "near_plane" |
| static constexpr auto | kPortIDFarPlane = "far_plane" |
| static constexpr auto | kPortIDHorizontalFov = "horizontal_fov" |
| static constexpr auto | kPortIDVerticalFov = "vertical_fov" |
| static constexpr auto | kPortIDMarkerNamespace = "marker_namespace" |
Additional Inherited Members | |
Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Publishes a visualization marker showing a camera frustum as a LINE_LIST.
Visualizes a camera frustum by publishing LINE_LIST markers showing the near plane, far plane, and the four connecting edges between them. The camera pose uses the optical frame convention: Z forward (viewing direction), X right, Y down.
Each instance gets a unique marker namespace (VisualizeCameraFrustum1, VisualizeCameraFrustum2, ...) so multiple frustums can coexist without overwriting each other.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| camera_pose | input | geometry_msgs::msg::PoseStamped |
| near_plane | input | double |
| far_plane | input | double |
| horizontal_fov | input | double |
| vertical_fov | input | double |
| marker_namespace | input | std::string |
| moveit_pro::behaviors::VisualizeCameraFrustum::VisualizeCameraFrustum | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
static |
|
static |
|
override |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |