C++ API (Doxygen via Breathe)

The C++ API documentation is generated by Doxygen and imported with Breathe. If the Doxygen XML is available, the top-level index will be shown below.

Note

The Read the Docs build runs doxygen Doxyfile in the docs folder as a pre-build step so the XML should be generated automatically.

struct DriverErrorCounters
#include <types.hpp>

Public Functions

inline void reset()

Public Members

uint64_t no_data = 0
uint64_t decode_failure = 0
uint64_t encode_failure = 0
uint64_t size_mismatch = 0
uint64_t serial_read_error = 0
uint64_t serial_write_error = 0
uint64_t invalid_control_char = 0
uint64_t no_command = 0
class ILittlebotDriver

Subclassed by littlebot_base::LittlebotDriver

Public Functions

ILittlebotDriver(const ILittlebotDriver&) = delete

Prevent copy and assignment.

ILittlebotDriver &operator=(const ILittlebotDriver&) = delete
virtual ~ILittlebotDriver() = default

Deconstructor for the ILittlebotDriver class.

virtual DriverError init() noexcept = 0

Initialize the driver.

Returns:

DriverError The result of the initialization

virtual void readRTData(WheelRTData &state) const noexcept = 0

Read the current state from the RT buffer.

Note

This method is RT-safe (control loop)

Parameters:

state – Reference to WheelRTData structure to store the read data

virtual void writeRTData(const WheelRTData &command) noexcept = 0

Write the command to the RT buffer.

Note

This method is RT-safe (control loop)

Parameters:

command – Reference to WheelRTData structure containing the command data

virtual bool requestStatus() noexcept = 0

Receive data from the hardware and update the RT buffer.

Note

This method is NOT RT-safe (executor / IO thread)

Returns:

true if data was received successfully

Returns:

false if an error occurred

virtual bool sendCommand() noexcept = 0

Send command data to the hardware.

Note

This method is NOT RT-safe (executor / IO thread)

Returns:

true if data was sent successfully

Returns:

false if an error occurred

virtual DriverError getLastError() const noexcept = 0

Get the last error that occurred.

Returns:

DriverError The last error code

virtual const DriverErrorCounters &getErrorCounters() const noexcept = 0

Get the error counters.

Returns:

const DriverErrorCounters& Reference to the error counters structure

Public Static Attributes

static constexpr char kCommandChar = {'C'}

Command control characters.

static constexpr char kStatusChar = {'S'}

Status control characters.

Protected Functions

ILittlebotDriver() = default

Default constructor for the ILittlebotDriver class.

class ILittlebotDriverFactory

Subclassed by littlebot_base::LittlebotDriverFactory

Public Functions

virtual ~ILittlebotDriverFactory() = default
virtual std::expected<std::shared_ptr<ILittlebotDriver>, DriverError> create(const std::string &port, int baudrate, const std::vector<std::string> &joint_names) = 0
template<typename T>
class IRTBuffer
#include <i_rt_buffer.hpp>

Public Functions

virtual ~IRTBuffer() = default
virtual const T *readRT() noexcept = 0
virtual void writeNonRT(const T &data) = 0
class ISerialPort
#include <i_serial_port.hpp>

Subclassed by littlebot_base::SerialPort

Public Functions

virtual ~ISerialPort() = default

Deconstructor for the ISerialPort class.

virtual SerialError open(std::string port, int baudrate) noexcept = 0

Open the serial port.

Parameters:
  • port – Serial port device path (e.g., “/dev/ttyUSB0”)

  • baudrate – Baud rate for the serial communication

Returns:

SerialError indicating success or type of failure

virtual SerialError close() noexcept = 0

Close the serial port.

Returns:

SerialError indicating success or type of failure

virtual int read(std::vector<uint8_t> &payload) noexcept = 0

Read Packet from the serial port.

Parameters:

payload – Vector to store the read packet data. Implementations must ensure the frame size never exceeds kMaxFrameSize.

Returns:

Number of bytes read

virtual int write(const std::vector<uint8_t> &payload) noexcept = 0

Write Packet to the serial port.

Parameters:

payload – Vector containing the packet data to write payload.size() must be <= kMaxFrameSize.

Returns:

Number of bytes written

inline virtual bool isOpen() const noexcept

Check if the serial port is open.

Returns:

true if the serial port is open

Returns:

false if the serial port is closed

Public Static Attributes

static constexpr size_t kMaxFrameSize = 256

Maximum size of a frame that can be sent/received.

Protected Functions

ISerialPort() = default

Constructor for the ISerialPort class.

ISerialPort(const ISerialPort&) = delete

Prevent copy and assignment.

ISerialPort &operator=(const ISerialPort&) = delete
virtual void readStream() noexcept = 0

Read data stream from the serial port.

virtual bool tryExtractFrame(std::vector<uint8_t> &payload) noexcept = 0

Get data from the received packet.

Parameters:

buffer – Shared pointer to string buffer to store received data

Returns:

true if a complete frame was extracted

Returns:

false if no complete frame was available

virtual void buildFrame(const std::vector<uint8_t> &payload, std::string &frame) noexcept = 0

Build packet to be sent through serial port.

Parameters:
  • payload – Vector containing the packet data to send

  • frame – String to store the built packet

Protected Attributes

std::vector<uint8_t> rx_buffer_

Buffer to store received data.

libserial::Serial serial_

Serial object from libserial.

bool is_open_ = {false}

Flag to indicate if the serial port is open.

Protected Static Attributes

static constexpr char kStartByte = {'['}

Character to start the message.

static constexpr char kEndByte = {']'}

Character to end the message.

class LittlebotDriver : public littlebot_base::ILittlebotDriver

Public Functions

LittlebotDriver(std::shared_ptr<ISerialPort> serial_port, std::shared_ptr<IRTBuffer<WheelRTData>> rt_state_buffer, std::shared_ptr<IRTBuffer<WheelRTData>> rt_command_buffer, const std::vector<std::string> &joint_names, std::string port, int baudrate)

Construct a new Littlebot Driver object.

Parameters:
  • serial_port – Shared pointer to the serial port interface

  • rt_state_buffer – Shared pointer to the real-time buffer interface for wheel state data

  • rt_command_buffer – Shared pointer to the real-time buffer interface for wheel command data

  • joint_names – Vector of joint names

  • port – Serial port name

  • baudrate – Serial port baudrate

~LittlebotDriver() override = default
virtual DriverError init() noexcept override

Initialize the driver.

Override the virtual method from ILittlebotDriver

virtual void readRTData(WheelRTData &state) const noexcept override

Read the current state from the RT buffer.

Override the virtual method from ILittlebotDriver

virtual void writeRTData(const WheelRTData &command) noexcept override

Write the command to the RT buffer.

Override the virtual method from ILittlebotDriver

virtual bool requestStatus() noexcept override

Receive data from the hardware and update the RT buffer.

Override the virtual method from ILittlebotDriver

virtual bool sendCommand() noexcept override

Send command data to the hardware.

Override the virtual method from ILittlebotDriver

inline virtual DriverError getLastError() const noexcept override

Get the last error that occurred.

Override the virtual method from ILittlebotDriver

inline virtual const DriverErrorCounters &getErrorCounters() const noexcept override

Get the error counters.

Override the virtual method from ILittlebotDriver

Private Members

DriverErrorCounters error_counters_

Error counters for the driver.

DriverError last_error_ = {DriverError::None}

Last error that occurred.

std::shared_ptr<ISerialPort> serial_port_

Serial port interface.

std::shared_ptr<IRTBuffer<WheelRTData>> rt_state_buffer_

RT buffer interface for wheel data states.

std::shared_ptr<IRTBuffer<WheelRTData>> rt_command_buffer_

RT buffer interface for wheel data commands.

std::string port_

Serial port name.

int baudrate_ = {0}

Serial port baudrate.

std::vector<littlebot_base::Wheel> wheels_

Vector of wheels (Not RT-safe)

Private Static Functions

static DriverError mapSerialError(SerialError error) noexcept

Map SerialError to DriverError.

Parameters:

error – SerialError to map

Returns:

DriverError Mapped DriverError

class LittlebotDriverFactory : public littlebot_base::ILittlebotDriverFactory

Public Functions

virtual std::expected<std::shared_ptr<ILittlebotDriver>, DriverError> create(const std::string &port, int baudrate, const std::vector<std::string> &joint_names) override
class LittlebotHardwareComponent : public hardware_interface::SystemInterface

Public Functions

LittlebotHardwareComponent() = default

Default constructor for the LittlebotHardwareComponent class.

~LittlebotHardwareComponent() = default

Deconstructor for the LittlebotHardwareComponent class.

hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params) override

Initialize the hardware component with the given parameters.

hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configure the hardware communication.

hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
std::vector<hardware_interface::StateInterface> export_state_interfaces() override

Export the state interfaces.

std::vector<hardware_interface::CommandInterface> export_command_interfaces() override

Export the command interfaces.

hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override

Read the state of the hardware component.

hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override

Write the command to the hardware component.

inline void setDriverFactory(std::shared_ptr<ILittlebotDriverFactory> factory)

Set the Littlebot driver factory.

Note

This method is mainly used for testing purposes

Parameters:

factory – Shared pointer to the Littlebot driver factory

Private Members

const std::string hardware_component_name_ = {"LittlebotHardwareComponent"}

The name of the hardware component.

std::shared_ptr<littlebot_base::ILittlebotDriver> littlebot_driver_

Shared pointer to the Littlebot driver.

std::shared_ptr<ILittlebotDriverFactory> driver_factory_

Shared pointer to the Littlebot driver factory.

std::shared_ptr<IRTBuffer<WheelRTData>> rt_state_buffer_

Shared pointer to the RT buffer for wheel states.

std::shared_ptr<IRTBuffer<WheelRTData>> rt_command_buffer_

Shared pointer to the RT buffer for wheel commands.

rclcpp::TimerBase::SharedPtr io_timer_

Non-RT IO timer.

std::string serial_port_name_

Serial port device name.

int serial_baudrate_ = {115200}

Serial port baudrate.

std::vector<double> hw_commands_velocities_

command interface.

std::vector<double> hw_status_positions_

position state interface.

std::vector<double> hw_status_velocities_

velocity state interface.

Private Static Attributes

static constexpr int kNumCommandInterface_ = {1}

constant for number of command interfaces.

static constexpr int kNumStateInterface_ = {2}

constant for number of state interfaces.

class RosRTBuffer : public littlebot_base::IRTBuffer<littlebot_base::WheelRTData>
#include <ros_rt_buffer.hpp>

Public Functions

inline virtual const littlebot_base::WheelRTData *readRT() noexcept override
inline virtual void writeNonRT(const littlebot_base::WheelRTData &data) override

Private Members

realtime_tools::RealtimeBuffer<littlebot_base::WheelRTData> buffer_
class SerialPort : public littlebot_base::ISerialPort
#include <serial_port.hpp>

Public Functions

virtual SerialError open(std::string port, int baudrate) noexcept override

Open the serial port.

Override the virtual method from ISerialPort

virtual SerialError close() noexcept override

Close the serial port.

Override the virtual method from ISerialPort

virtual int read(std::vector<uint8_t> &payload) noexcept override

Read packet data from the serial port.

Override the virtual method from ISerialPort

virtual int write(const std::vector<uint8_t> &payload) noexcept override

Write packet data to the serial port.

Override the virtual method from ISerialPort

Private Functions

virtual void readStream() noexcept override

Read data stream from the serial port.

virtual bool tryExtractFrame(std::vector<uint8_t> &payload) noexcept override

Get data from the received packet.

Parameters:

buffer – Shared pointer to string buffer to store received data

virtual void buildFrame(const std::vector<uint8_t> &payload, std::string &frame) noexcept override

Build packet to be sent through serial port.

Parameters:

buffer – Shared pointer to string buffer to store data to be sent

Private Members

std::string port_path_ = {"/dev/rfcomm0"}

Serial port device path (e.g., “/dev/ttyUSB0”)

int baudrate_ = {115200}

Communication baudrate (e.g., 9600, 115200)

Private Static Attributes

static constexpr size_t kMaxReadChunk = {ISerialPort::kMaxFrameSize}

Maximum number of bytes to read in one chunk.

class Wheel
#include <wheel.hpp>

Public Functions

Wheel() = default
inline explicit Wheel(std::string joint_name)
~Wheel() = default
inline void setCommandVelocity(double velocity)

Set the command velocity for the wheel.

Parameters:

velocity – Desired command velocity

inline void setJointName(const std::string &joint_name)

Set the joint name for the wheel.

Parameters:

joint_name – Name of the joint

inline void setStatusVelocity(double velocity)

Set the status velocity for the wheel.

Parameters:

velocity – Measured status velocity

inline void setStatusPosition(double position)

Set the status position for the wheel.

Parameters:

position – Measured status position

inline double getCommandVelocity() const

Get the command velocity for the wheel.

inline double getStatusPosition() const

Get the status position for the wheel.

inline double getStatusVelocity() const

Get the status velocity for the wheel.

inline std::string getJointName() const

Get the joint name for the wheel.

Private Members

double status_vel_ = {0.0}

Status velocity of the wheel.

double status_pos_ = {0.0}

Status position of the wheel.

double command_vel_ = {0.0}

Command velocity of the wheel.

std::string joint_name_ = {"wheel"}

Joint name of the wheel.

struct WheelRTData
#include <types.hpp>

Public Members

std::array<float, kNumWheels> command_velocity = {}
std::array<float, kNumWheels> status_velocity = {}
std::array<float, kNumWheels> status_position = {}
namespace hardware_interface
namespace littlebot_base

To more information about the serial library used, please visit: https://github.com/NestorDP/cppserial.

Enums

enum class SerialError

Values:

enumerator None
enumerator PortUnavailable
enumerator InsufficientPermissions
enumerator ConfigBaudrateFailed
enumerator ReadFailed
enumerator WriteFailed
enumerator AlreadyOpen
enumerator NotOpen
enumerator NotClosed
enumerator Unknown
enum class DriverError

Values:

enumerator None
enumerator NoData
enumerator DecodeFailure
enumerator EncodeFailure
enumerator SizeMismatch
enumerator SerialReadError
enumerator SerialWriteError
enumerator InvalidControlChar
enumerator NoCommand
enumerator SerialPortUnavailable
enumerator SerialInsufficientPermissions
enumerator SerialConfigBaudrateFailed
enumerator SerialReadFailed
enumerator SerialWriteFailed
enumerator SerialAlreadyOpen
enumerator SerialNotOpen
enumerator SerialNotClosed
enumerator Unknown

Variables

constexpr size_t kNumWheels = 2
namespace codec

Functions

void encode(std::vector<uint8_t> &payload, const std::vector<Wheel> &wheels)

Encode wheel command data into a protobuf payload.

This function serializes the command velocities of the wheels into a protobuf message suitable for transmission to the hardware.

Parameters:
  • payload – Output payload that will contain the serialized protobuf message

  • wheels – Vector of wheels providing command data

Throws:

std::runtime_error – if serialization fails

void decode(const std::vector<uint8_t> &payload, std::vector<Wheel> &wheels)

Decode wheel state data from a protobuf payload.

This function deserializes a protobuf message received from the hardware and updates the wheel status fields. Existing wheel metadata (e.g., joint names) is preserved.

Parameters:
  • payload – Input payload containing the serialized protobuf message

  • wheels – Vector of wheels to be updated with decoded state data

Throws:

std::runtime_error – if parsing fails or data size mismatches

file codec.hpp
#include <iostream>
#include <memory>
#include <string>
#include <vector>
#include “littlebot_msg.pb.h”
#include “littlebot_base/wheel.hpp
file i_littlebot_driver.hpp
#include <memory>
#include <string>
#include <vector>
#include “littlebot_base/types.hpp
#include “littlebot_base/wheel.hpp
file i_littlebot_driver_factory.hpp
#include <expected>
#include <memory>
#include <string>
#include <vector>
#include “littlebot_base/types.hpp
file i_rt_buffer.hpp
file i_serial_port.hpp
#include <cstdint>
#include <memory>
#include <string>
#include <vector>
#include “libserial/serial.hpp”
file littlebot_driver.hpp
#include <memory>
#include <string>
#include <vector>
#include “littlebot_base/types.hpp
#include “littlebot_base/wheel.hpp
file littlebot_driver_factory.hpp
#include <expected>
#include <memory>
#include <string>
#include <vector>
file littlebot_hardware_component.hpp
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>
#include “hardware_interface/handle.hpp”
#include “hardware_interface/hardware_info.hpp”
#include “hardware_interface/system_interface.hpp”
#include “hardware_interface/types/hardware_interface_return_values.hpp”
#include “rclcpp/clock.hpp”
#include “rclcpp/duration.hpp”
#include “rclcpp/macros.hpp”
#include “rclcpp/time.hpp”
#include “rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp”
#include “rclcpp_lifecycle/state.hpp”
#include “littlebot_base/types.hpp
file ros_rt_buffer.hpp
#include “realtime_tools/realtime_buffer.hpp”
#include “littlebot_base/types.hpp
file serial_port.hpp
#include <iostream>
#include <memory>
#include <string>
#include <vector>
file types.hpp
#include <array>
#include <cstddef>
#include <cstdint>
file wheel.hpp
#include <iostream>
#include <memory>
#include <string>
#include <utility>
#include <vector>
file codec.cpp
#include <stdexcept>
#include “littlebot_base/codec.hpp
file littlebot_driver.cpp
#include “littlebot_base/codec.hpp
file littlebot_driver_factory.cpp
file littlebot_hardware_component.cpp
#include <hardware_interface/lexical_casts.hpp>
#include <hardware_interface/types/hardware_interface_type_values.hpp>
#include <rclcpp/rclcpp.hpp>
#include “pluginlib/class_list_macros.hpp”
file serial_port.cpp
#include <algorithm>
dir /home/docs/checkouts/readthedocs.org/user_builds/littlebot/checkouts/latest/littlebot_base/include
dir /home/docs/checkouts/readthedocs.org/user_builds/littlebot/checkouts/latest/littlebot_base
dir /home/docs/checkouts/readthedocs.org/user_builds/littlebot/checkouts/latest/littlebot_base/include/littlebot_base
dir /home/docs/checkouts/readthedocs.org/user_builds/littlebot/checkouts/latest/littlebot_base/src