Class Path2DPublisher
- Defined in File path_2d_publisher.hpp 
Inheritance Relationships
Base Type
- public fuse_core::AsyncPublisher
Class Documentation
- 
class Path2DPublisher : public fuse_core::AsyncPublisher
- Publisher plugin that publishes all of the stamped 2D poses as a nav_msgs::msg::Path message. - Parameters: - device_id (uuid string, default: 00000000-0000-0000-0000-000000000000) The device/robot ID to publish 
- device_name (string) Used to generate the device/robot ID if the device_id is not provided 
- frame_id (string, default: map) Name for the robot’s map frame 
 - Public Functions - 
Path2DPublisher()
- Constructor. 
 - 
virtual ~Path2DPublisher() = default
- Destructor. 
 - 
void initialize(fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces, const std::string &name) override
- Shadowing extension to the AsyncPublisher::initialize call. 
 - 
void onInit() override
- Perform any required post-construction initialization, such as advertising publishers or reading from the parameter server. 
 - Notify the publisher about variables that have been added or removed. - Parameters:
- transaction – [in] A Transaction object, describing the set of variables that have been added and/or removed 
- graph – [in] A read-only pointer to the graph object, allowing queries to be performed whenever needed 
 
 
 - Protected Attributes - 
fuse_core::node_interfaces::NodeInterfaces<fuse_core::node_interfaces::Base, fuse_core::node_interfaces::Parameters, fuse_core::node_interfaces::Topics, fuse_core::node_interfaces::Waitables> interfaces_
- Shadows AsyncPublisher interfaces_. 
 - 
fuse_core::UUID device_id_
- The UUID of the device to be published. 
 - 
std::string frame_id_
- The name of the frame for this path. - The publisher that sends the entire robot trajectory as a path 
 - 
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr path_publisher_
- The publisher that sends the entire robot trajectory as a pose array. 
 - 
rclcpp::Publisher<geometry_msgs::msg::PoseArray>::SharedPtr pose_array_publisher_