PolygonObject Message
Package: nav2_msgs
Category: Other Messages
Nav2 message for robotic navigation and behavior control
Message Definition
Field | Type | Description |
---|---|---|
header |
std_msgs/Header |
Standard ROS header with timestamp and frame information |
uuid |
unique_identifier_msgs/UUID |
Message field - see Nav2 documentation for specific usage details |
points |
geometry_msgs/Point32[] |
Array of geometry_msgs/Point32 values |
closed |
bool |
Boolean true/false value |
value |
int8 |
Message field - see Nav2 documentation for specific usage details |
Usage Examples
Python
import rclpy
from rclpy.node import Node
from nav2_msgs.msg import PolygonObject
class PolygonObjectPublisher(Node):
def __init__(self):
super().__init__('polygonobject_publisher')
self.publisher = self.create_publisher(PolygonObject, 'polygonobject', 10)
def publish_message(self):
msg = PolygonObject()
msg.header.frame_id = 'map'
msg.header.stamp = self.get_clock().now().to_msg()
# Set msg.uuid as needed
msg.points = [] # Fill array as needed
msg.closed = True
# Set msg.value as needed
self.publisher.publish(msg)
C++
#include "rclcpp/rclcpp.hpp"
#include "nav2_msgs/msg/polygon_object.hpp"
class PolygonObjectPublisher : public rclcpp::Node
{
public:
PolygonObjectPublisher() : Node("polygonobject_publisher")
{
publisher_ = create_publisher<nav2_msgs::msg::PolygonObject>("polygonobject", 10);
}
void publish_message()
{
auto msg = nav2_msgs::msg::PolygonObject();
msg.header.frame_id = "map";
msg.header.stamp = this->now();
// Set msg.uuid as needed
// Fill msg.points array as needed
msg.closed = true;
// Set msg.value as needed
publisher_->publish(msg);
}
private:
rclcpp::Publisher<nav2_msgs::msg::PolygonObject>::SharedPtr publisher_;
};