|
TinyRobotics
|
micro-ROS interface for vehicle control and odometry on Arduino/ESP32. More...
#include <MicroROS.h>


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) |
micro-ROS interface for vehicle control and odometry on Arduino/ESP32.
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:
|
inlineprotectedvirtual |
Reimplemented from MessageHandler.
|
inlineoverrideprotectedvirtual |
Handle an incoming message (pure virtual).
This method should be implemented by derived classes to process messages.
| msg | The message to handle. |
Implements MessageHandler.
|
inlineoverrideprotectedvirtual |
Reimplemented from MessageHandler.