TinyRobotics
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
MicroROS Class Reference

micro-ROS interface for vehicle control and odometry on Arduino/ESP32. More...

#include <MicroROS.h>

Inheritance diagram for MicroROS:
Inheritance graph
[legend]
Collaboration diagram for MicroROS:
Collaboration graph
[legend]

Public Member Functions

 MicroROS (const char *node_name="tinyrobotics_node")
 
void setCallback (void(*cb)(const void *msgin))
 
bool begin ()
 
bool sendOdometry (const nav_msgs__msg__Odometry &msg)
 Publish odometry message.
 
bool sendOdometry (const MotionState3D state)
 Publish odometry message.
 
bool sendOdometry (Coordinate< DistanceM > position, Orientation3D orientation)
 Publish odometry message.
 
bool sendPoint (const geometry_msgs__msg__Point32 &msg)
 Publish Point32 (occupancy grid map message not available in micro-ROS)
 
bool sendCoordinate (const Coordinate< DistanceM > &coordinate)
 
template<typename T >
bool sendMap (IMap< T > &entry)
 Publish Point32 (occupancy grid map message not available in micro-ROS)
 
rclc_executor_t & getExecutor ()
 
- Public Member Functions inherited from MessageHandler
virtual bool onMessage (const Message< float > &msg)=0
 Handle an incoming message (pure virtual).
 
virtual bool onMessage (const Message< Coordinate< float > > &msg)
 
virtual bool onMessage (const Message< GPSCoordinate > &msg)
 
virtual bool onMessage (const Message< MotionState3D > &msg)
 

Protected Member Functions

bool onMessage (const Message< float > &msg) override
 Handle an incoming message (pure virtual).
 
bool onMessage (const Message< MotionState3D > &msg) override
 
bool onMessage (const Message< Coordinate< float > > &msg)
 

Protected Attributes

const char * ros_node_name = nullptr
 
void(* cmd_callback )(const void *msgin) = nullptr
 
bool is_tranport_defined = false
 
rcl_node_t node
 
rclc_executor_t executor
 
rclc_support_t support
 
rcl_allocator_t allocator
 
rcl_subscription_t sub_cmd
 
rcl_publisher_t publisher
 
geometry_msgs__msg__Twist cmd_msg
 

Detailed Description

micro-ROS interface for vehicle control and odometry on Arduino/ESP32.

Note
Install the micro_ros_arduino library

This class sets up a micro-ROS node e.g. for an Ackermann steering robot, subscribing to velocity commands (geometry_msgs/Twist on /cmd_vel) and publishing odometry (nav_msgs/Odometry on /odom).

Features:

Usage:

  1. Call setCallback() to provide a function for handling incoming /cmd_vel messages.
  2. Call begin() to initialize micro-ROS and set up publishers/subscribers.
  3. Periodically call sendOdometry() in your main loop to process messages and publish odometry.
Note
optional functionality: include "TinyRobotics/communication/MicroROS.h"
Author
Phil Schatzmann
Date
2026-03-30

Member Function Documentation

◆ onMessage() [1/3]

bool onMessage ( const Message< Coordinate< float > > &  msg)
inlineprotectedvirtual

Reimplemented from MessageHandler.

◆ onMessage() [2/3]

bool onMessage ( const Message< float > &  msg)
inlineoverrideprotectedvirtual

Handle an incoming message (pure virtual).

This method should be implemented by derived classes to process messages.

Parameters
msgThe message to handle.
Returns
true if the message was handled successfully, false otherwise.

Implements MessageHandler.

◆ onMessage() [3/3]

bool onMessage ( const Message< MotionState3D > &  msg)
inlineoverrideprotectedvirtual

Reimplemented from MessageHandler.


The documentation for this class was generated from the following file: