CircleObject 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
center geometry_msgs/Point32 Message field - see Nav2 documentation for specific usage details
radius float32 Floating point numerical value
fill 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 CircleObject

class CircleObjectPublisher(Node):
    def __init__(self):
        super().__init__('circleobject_publisher')
        self.publisher = self.create_publisher(CircleObject, 'circleobject', 10)
        
    def publish_message(self):
        msg = CircleObject()
        msg.header.frame_id = 'map'
        msg.header.stamp = self.get_clock().now().to_msg()
        # Set msg.uuid as needed
        # Set msg.center as needed
        msg.radius = 0.0
        msg.fill = True
        # Set msg.value as needed
        self.publisher.publish(msg)

C++

#include "rclcpp/rclcpp.hpp"
#include "nav2_msgs/msg/circle_object.hpp"

class CircleObjectPublisher : public rclcpp::Node
{
public:
    CircleObjectPublisher() : Node("circleobject_publisher")
    {
        publisher_ = create_publisher<nav2_msgs::msg::CircleObject>("circleobject", 10);
    }

    void publish_message()
    {
        auto msg = nav2_msgs::msg::CircleObject();
        msg.header.frame_id = "map";
        msg.header.stamp = this->now();
        // Set msg.uuid as needed
        // Set msg.center as needed
        msg.radius = 0.0;
        msg.fill = true;
        // Set msg.value as needed
        publisher_->publish(msg);
    }

private:
    rclcpp::Publisher<nav2_msgs::msg::CircleObject>::SharedPtr publisher_;
};