From 5a0a1464c7871efe65250380e054bc0fd48d2ee7 Mon Sep 17 00:00:00 2001 From: NestorDP Date: Thu, 28 Nov 2024 22:02:02 -0300 Subject: [PATCH] Proto buffers basic --- .gitignore | 1 + .../littlebot_communication.hpp | 86 ----- .../littlebot_base/littlebot_hardware.hpp | 54 +-- littlebot_base/scripts/littlebot_fake.py | 57 +++ littlebot_base/scripts/littlebot_mock.py | 26 -- .../src/littlebot_communication.cpp | 58 --- littlebot_base/src/littlebot_hardware.cpp | 353 +++++++----------- littlebot_base/src/littlebot_protocol.proto | 23 ++ 8 files changed, 213 insertions(+), 445 deletions(-) delete mode 100755 littlebot_base/include/littlebot_base/littlebot_communication.hpp create mode 100755 littlebot_base/scripts/littlebot_fake.py delete mode 100755 littlebot_base/scripts/littlebot_mock.py delete mode 100755 littlebot_base/src/littlebot_communication.cpp create mode 100644 littlebot_base/src/littlebot_protocol.proto diff --git a/.gitignore b/.gitignore index 958956a..d79901f 100755 --- a/.gitignore +++ b/.gitignore @@ -33,3 +33,4 @@ .vscode/ +*__pycache__/ diff --git a/littlebot_base/include/littlebot_base/littlebot_communication.hpp b/littlebot_base/include/littlebot_base/littlebot_communication.hpp deleted file mode 100755 index 1181bf6..0000000 --- a/littlebot_base/include/littlebot_base/littlebot_communication.hpp +++ /dev/null @@ -1,86 +0,0 @@ -// @ Copyright 2022 Nestor Neto - -/** - * @mainpage Serial Interface Library - * @section intro_sec Indroduction - * This is an interface C++ library for serial serial - * - * - */ -#ifndef LITTLEBOT_BASE_INCLUDE_LITTLEBOT_BASE_PROTOCOL_HPP_ -#define LITTLEBOT_BASE_INCLUDE_LITTLEBOT_BASE_PROTOCOL_HPP_ - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - - -namespace littlebot { - -class Protocol { - public: - Protocol(); - /** - * @brief Constructor of the serial class - * - */ - explicit Protocol(std::string port); - - /** - * @brief Destroyer of the serial class - * - */ - ~Protocol(); - - /** - * @brief - * - */ - void Read(void); - - /** - * @brief - * - */ - void Write(void); - - /** - * @brief - * - */ - void SetVelocity(float dir, float lef); - - /** - * @brief - * - */ - void GetVelocity(float *dir, float *lef); - - - private: - /** Length of buffer */ - const int kLengthBuffer_ = 200; - - /** Port */ - serial::Serial port_; - - /** Buffer */ - std::string msg_protocol_; - - /** */ - float velocity_read_[2]; - float velocity_write_[2]; -}; -} // namespace littlebot - -#endif // LITTLEBOT_BASE_INCLUDE_LITTLEBOT_BASE_PROTOCOL_HPP_ diff --git a/littlebot_base/include/littlebot_base/littlebot_hardware.hpp b/littlebot_base/include/littlebot_base/littlebot_hardware.hpp index e4ce3b9..c180acb 100644 --- a/littlebot_base/include/littlebot_base/littlebot_hardware.hpp +++ b/littlebot_base/include/littlebot_base/littlebot_hardware.hpp @@ -26,7 +26,7 @@ class LittlebotHardwareComponent : public hardware_interface::SystemInterface * @brief Deconstructor for the LittlebotHardwareComponent class * */ - // ~LittlebotHardwareComponent() override; + ~LittlebotHardwareComponent() = default; /** * @brief @@ -34,36 +34,18 @@ class LittlebotHardwareComponent : public hardware_interface::SystemInterface hardware_interface::CallbackReturn on_init( const hardware_interface::HardwareInfo & info) override; - /** - * @brief - */ - hardware_interface::CallbackReturn on_configure( - const rclcpp_lifecycle::State & state) override; - /** * @brief */ hardware_interface::CallbackReturn on_activate( const rclcpp_lifecycle::State & state) override; - /** - * @brief - */ - hardware_interface::CallbackReturn on_shutdown( - const rclcpp_lifecycle::State & state) override; - /** * @brief */ hardware_interface::CallbackReturn on_deactivate( const rclcpp_lifecycle::State & state) override; - /** - * @brief - */ - hardware_interface::CallbackReturn on_error( - const rclcpp_lifecycle::State & state) override; - /** * @brief */ @@ -117,40 +99,6 @@ class LittlebotHardwareComponent : public hardware_interface::SystemInterface * @brief */ static constexpr int kNumStateInterface_{2}; - - - - - - - - - - - - /** - * @brief - */ - //std::shared_ptr littlebot_communication_ptr_; - - /** - * @brief The name of the package where the communication plugin is implemented. - * - */ - //const std::string communication_plugin_package_name_{"littlebot_base"}; - - /** - * @brief The name of the communication plugin. - * - */ - //std::string communication_plugin_name_{""}; - - /** - * @brief The base class of the communication plugin. - * - */ - //const std::string communication_plugin_base_class_{"LittlebotCommunicationInterface"}; - }; } // namespace littlebot_base \ No newline at end of file diff --git a/littlebot_base/scripts/littlebot_fake.py b/littlebot_base/scripts/littlebot_fake.py new file mode 100755 index 0000000..37e5522 --- /dev/null +++ b/littlebot_base/scripts/littlebot_fake.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +""" +Created on Mon Mar 26 09:09:20 2018 + +@author: nestor +""" + +import base64 +import serial +import sys + +import todolist_pb2 as TodoList + +serial_port = sys.argv[1] + +ser = serial.Serial(serial_port, baudrate=115200) # open serial port + +start_character = b'<' +end_character = b'>' + +# Create a new TodoList +my_list = TodoList.TodoList() +my_list.owner_id = 1234 + +my_list.owner_name = "Tim" + +first_item = my_list.todos.add() +first_item.state = TodoList.TaskState.Value("TASK_DONE") +first_item.task = "Test ProtoBuf for Python" +first_item.due_date = "31.10.2019" + +# Serialize the TodoList and send it over the serial port +encoded_data = start_character + my_list.SerializeToString() + end_character +ser.write(encoded_data) +print(f"Encoded data sent: {encoded_data}\n") + +ser.flush() + +my_list2 = TodoList.TodoList() + +# Read the encoded data from the serial port +data = ser.read() +if data == start_character: + encoded_data_received = ser.read_until(end_character) + +# Debugging print +print(f"Encoded data received: {encoded_data_received}") + +# Parse the decoded data into a TodoList +try: + my_list2.ParseFromString(encoded_data_received[:-1]) + print(my_list2) +except Exception as e: + print(f"Failed to parse the message: {e}") + +ser.close() \ No newline at end of file diff --git a/littlebot_base/scripts/littlebot_mock.py b/littlebot_base/scripts/littlebot_mock.py deleted file mode 100755 index 4a00b97..0000000 --- a/littlebot_base/scripts/littlebot_mock.py +++ /dev/null @@ -1,26 +0,0 @@ -#!/usr/bin/env python3 -# -*- coding: utf-8 -*- -""" -Created on Mon Mar 26 09:09:20 2018 - -@author: nestor -""" - -import serial -import sys - -serial_port = sys.argv[1] - -ser = serial.Serial(serial_port, baudrate=115200) # open serial port - -ser.write(str("hello\n").encode()) # write a string -ser.flush() -while True: - # Read one line from the serial port - if ser.in_waiting > 0: - data = ser.readline().decode('utf-8').rstrip() - print(f"Received: {data}") - if data == "exit": - break - -ser.close() \ No newline at end of file diff --git a/littlebot_base/src/littlebot_communication.cpp b/littlebot_base/src/littlebot_communication.cpp deleted file mode 100755 index 27ba211..0000000 --- a/littlebot_base/src/littlebot_communication.cpp +++ /dev/null @@ -1,58 +0,0 @@ -// @ Copyright 2023 Nestor Neto - -#include "littlebot_base/littlebot_communication.hpp" - -namespace littlebot { - -Protocol::Protocol() {} - -Protocol::Protocol(std::string port) { - port_.OpenPort(port.c_str()); -} - -Protocol::~Protocol() {} - -void Protocol::Read(void) { - float *a, *b; - port_.ReceiveMsg(&msg_protocol_); - a = reinterpret_cast (msg_protocol_.c_str()); - b = reinterpret_cast (msg_protocol_.c_str() + 4); - velocity_read_[0] = *a; - velocity_read_[1] = *b; - std::cout << msg_protocol_ << std::endl; -} - -void Protocol::Write(void) { - // unsigned int i; - // char vel_dir[sizeof(float)]; - // char vel_lef[sizeof(float)]; - // char *ptr; - - // std::shared_ptr msg_ptr; - // std::ostringstream msg; - - // ptr = reinterpret_cast(&velocity_write_[0]); - // for (i = 0; i < sizeof(float); i++){ - // vel_dir[i] = *(ptr + i); - // } - - // ptr = reinterpret_cast(&velocity_write_[1]); - // for (i = 0; i < sizeof(float); i++){ - // vel_lef[i] = *(ptr + i); - // } - - // msg << vel_dir << '#' << vel_lef; - // port_.SendMsg(std::make_shared(msg.str())); -} - -void Protocol::SetVelocity(float dir, float lef) { - velocity_write_[0] = dir; - velocity_write_[1] = lef; -} - - -void Protocol::GetVelocity(float *dir, float *lef) { - *dir = velocity_read_[0]; - *lef = velocity_read_[1]; -} -} // namespace littlebot diff --git a/littlebot_base/src/littlebot_hardware.cpp b/littlebot_base/src/littlebot_hardware.cpp index fc6be61..acfd7ef 100644 --- a/littlebot_base/src/littlebot_hardware.cpp +++ b/littlebot_base/src/littlebot_hardware.cpp @@ -1,5 +1,7 @@ -// // @ Copyright 2023 Nestor Neto +// @ Copyright 2023 Nestor Neto +#include "hardware_interface/lexical_casts.hpp" +#include #include #include "littlebot_base/littlebot_hardware.hpp" @@ -7,229 +9,136 @@ namespace littlebot_base { -// // LittlebotHardwareComponent::~LittlebotHardwareComponent() -// // { -// // } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_init( -// const hardware_interface::HardwareInfo & info) -// { -// if (hardware_interface::SystemInterface::on_init(info) != -// hardware_interface::CallbackReturn::SUCCESS) -// { -// return hardware_interface::CallbackReturn::FAILURE; -// } +hardware_interface::CallbackReturn LittlebotHardwareComponent::on_init( + const hardware_interface::HardwareInfo & info) +{ + if (hardware_interface::SystemInterface::on_init(info) != + hardware_interface::CallbackReturn::SUCCESS) + { + return hardware_interface::CallbackReturn::FAILURE; + } -// hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); -// hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); -// hw_commands_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); - -// for (const hardware_interface::ComponentInfo & joint : info_.joints) -// { -// if (joint.command_interfaces.size() != kNumCommandInterface_) -// { -// RCLCPP_FATAL( -// rclcpp::get_logger("LittlebotSystemHardware"), -// "Joint '%s' has %zu command interfaces found. 1 expected.", joint.name.c_str(), -// joint.command_interfaces.size()); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// if (joint.command_interfaces[0].name != hardware_interface::HW_IF_VELOCITY) -// { -// RCLCPP_FATAL( -// rclcpp::get_logger("LittlebotSystemHardware"), -// "Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(), -// joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_VELOCITY); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// if (joint.state_interfaces.size() != kNumStateInterface_) -// { -// RCLCPP_FATAL( -// rclcpp::get_logger("LittlebotSystemHardware"), -// "Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(), -// joint.state_interfaces.size()); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) -// { -// RCLCPP_FATAL( -// rclcpp::get_logger("LittlebotSystemHardware"), -// "Joint '%s' have %s state interfaces found. '%s' expected.", joint.name.c_str(), -// joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY) -// { -// RCLCPP_FATAL( -// rclcpp::get_logger("LittlebotSystemHardware"), -// "Joint '%s' have %s state interfaces found. '%s' expected.", joint.name.c_str(), -// joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY); -// return hardware_interface::CallbackReturn::ERROR; -// } -// } + hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); + hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); + hw_commands_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); + + for (const hardware_interface::ComponentInfo & joint : info_.joints) + { + if (joint.command_interfaces.size() != kNumCommandInterface_) + { + RCLCPP_FATAL( + rclcpp::get_logger("LittlebotSystemHardware"), + "Joint '%s' has %zu command interfaces found. 1 expected.", joint.name.c_str(), + joint.command_interfaces.size()); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.command_interfaces[0].name != hardware_interface::HW_IF_VELOCITY) + { + RCLCPP_FATAL( + rclcpp::get_logger("LittlebotSystemHardware"), + "Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(), + joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_VELOCITY); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces.size() != kNumStateInterface_) + { + RCLCPP_FATAL( + rclcpp::get_logger("LittlebotSystemHardware"), + "Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(), + joint.state_interfaces.size()); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION) + { + RCLCPP_FATAL( + rclcpp::get_logger("LittlebotSystemHardware"), + "Joint '%s' have %s state interfaces found. '%s' expected.", joint.name.c_str(), + joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY) + { + RCLCPP_FATAL( + rclcpp::get_logger("LittlebotSystemHardware"), + "Joint '%s' have %s state interfaces found. '%s' expected.", joint.name.c_str(), + joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY); + return hardware_interface::CallbackReturn::ERROR; + } + } -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_configure( -// [[maybe_unused]] const rclcpp_lifecycle::State & state) -// { -// if (manipulator_communication_ptr_ == nullptr) { -// RCLCPP_FATAL( -// rclcpp::get_logger( -// hardware_component_name_), "The Bravo Seven Communication plugin is not set."); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// try { -// manipulator_communication_ptr_->openConnection(uri_, read_timeout_, write_timeout_); -// } catch (const std::exception & e) { -// RCLCPP_FATAL( -// rclcpp::get_logger(hardware_component_name_), "Error while opening connection: %s", e.what()); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// try { -// this->configureLimitsOfJoints(); -// } catch (const std::exception & e) { -// RCLCPP_FATAL( -// rclcpp::get_logger(hardware_component_name_), -// "Error while configuring the manipulator joints: %s", e.what()); -// return hardware_interface::CallbackReturn::ERROR; -// } - -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_activate( -// [[maybe_unused]] const rclcpp_lifecycle::State & state) -// { -// // set some default values -// for (auto i = 0u; i < hw_positions_.size(); i++) -// { -// if (std::isnan(hw_positions_[i])) -// { -// hw_positions_[i] = 0; -// hw_velocities_[i] = 0; -// hw_commands_[i] = 0; -// } -// } - -// RCLCPP_INFO(rclcpp::get_logger("LittlebotSystemHardware"), "Successfully activated!"); - -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_shutdown( -// [[maybe_unused]] const rclcpp_lifecycle::State & state) -// { -// if (manipulator_communication_ptr_->isConnectionOpen()) { -// manipulator_communication_ptr_->closeConnection(); -// } - -// RCLCPP_INFO( -// rclcpp::get_logger( -// hardware_component_name_), "BravoSevenHardware successfully shut down"); - -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_deactivate( -// [[maybe_unused]] const rclcpp_lifecycle::State & state) -// { -// RCLCPP_INFO(rclcpp::get_logger("LittlebotSystemHardware"), "Successfully deactivated!"); - -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// hardware_interface::CallbackReturn LittlebotHardwareComponent::on_error( -// [[maybe_unused]] const rclcpp_lifecycle::State & state) -// { -// if (manipulator_communication_ptr_->isConnectionOpen()) { -// manipulator_communication_ptr_->closeConnection(); -// } - -// RCLCPP_INFO( -// rclcpp::get_logger( -// hardware_component_name_), "BravoSevenHardware successfully recovered from error state."); - -// return hardware_interface::CallbackReturn::SUCCESS; -// } - -// std::vector LittlebotHardwareComponent::export_state_interfaces() -// { -// std::vector state_interfaces; -// for (auto i = 0u; i < info_.joints.size(); i++) -// { -// state_interfaces.emplace_back(hardware_interface::StateInterface( -// info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_[i])); -// state_interfaces.emplace_back(hardware_interface::StateInterface( -// info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_[i])); -// } - -// return state_interfaces; -// } - -// std::vector DiffBotSystemHardware::export_command_interfaces() -// { -// std::vector command_interfaces; -// for (auto i = 0u; i < info_.joints.size(); i++) -// { -// command_interfaces.emplace_back(hardware_interface::CommandInterface( -// info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_commands_[i])); -// } - -// return command_interfaces; -// } - -// hardware_interface::return_type LittlebotHardwareComponent::read( -// [[maybe_unused]] const rclcpp::Time & time, -// [[maybe_unused]] const rclcpp::Duration & period) -// { -// // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code -// for (std::size_t i = 0; i < hw_velocities_.size(); i++) -// { -// // Simulate DiffBot wheels's movement as a first-order system -// // Update the joint status: this is a revolute joint without any limit. -// // Simply integrates -// hw_positions_[i] = hw_positions_[i] + period.seconds() * hw_velocities_[i]; - -// RCLCPP_INFO( -// rclcpp::get_logger("DiffBotSystemHardware"), -// "Got position state %.5f and velocity state %.5f for '%s'!", hw_positions_[i], -// hw_velocities_[i], info_.joints[i].name.c_str()); -// } -// // END: This part here is for exemplary purposes - Please do not copy to your production code - -// return hardware_interface::return_type::OK; -// } - - -// hardware_interface::return_type LittlebotHardwareComponent::write( -// [[maybe_unused]] const rclcpp::Time & time, -// [[maybe_unused]] const rclcpp::Duration & period) -// { -// // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code -// RCLCPP_INFO(rclcpp::get_logger("DiffBotSystemHardware"), "Writing..."); - -// for (auto i = 0u; i < hw_commands_.size(); i++) -// { -// // Simulate sending commands to the hardware -// RCLCPP_INFO( -// rclcpp::get_logger("DiffBotSystemHardware"), "Got command %.5f for '%s'!", hw_commands_[i], -// info_.joints[i].name.c_str()); - -// hw_velocities_[i] = hw_commands_[i]; -// } -// RCLCPP_INFO(rclcpp::get_logger("DiffBotSystemHardware"), "Joints successfully written!"); -// // END: This part here is for exemplary purposes - Please do not copy to your production code - -// return hardware_interface::return_type::OK; -// } + return hardware_interface::CallbackReturn::SUCCESS; +} + +hardware_interface::CallbackReturn LittlebotHardwareComponent::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + for (auto i = 0u; i < hw_positions_.size(); i++) + { + if (std::isnan(hw_positions_[i])) + { + hw_positions_[i] = 0; + hw_velocities_[i] = 0; + hw_commands_[i] = 0; + } + } + + RCLCPP_INFO(rclcpp::get_logger("LittlebotSystemHardware"), "Successfully activated!"); + + return hardware_interface::CallbackReturn::SUCCESS; +} + +hardware_interface::CallbackReturn LittlebotHardwareComponent::on_deactivate( + [[maybe_unused]] const rclcpp_lifecycle::State & state) +{ + RCLCPP_INFO(rclcpp::get_logger("LittlebotSystemHardware"), "Successfully deactivated!"); + + return hardware_interface::CallbackReturn::SUCCESS; +} + +std::vector LittlebotHardwareComponent::export_state_interfaces() +{ + std::vector state_interfaces; + for (auto i = 0u; i < info_.joints.size(); i++) + { + state_interfaces.emplace_back(hardware_interface::StateInterface( + info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_[i])); + state_interfaces.emplace_back(hardware_interface::StateInterface( + info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_[i])); + } + + return state_interfaces; +} + +std::vector LittlebotHardwareComponent::export_command_interfaces() +{ + std::vector command_interfaces; + for (auto i = 0u; i < info_.joints.size(); i++) + { + command_interfaces.emplace_back(hardware_interface::CommandInterface( + info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_commands_[i])); + } + + return command_interfaces; +} + +hardware_interface::return_type LittlebotHardwareComponent::read( + [[maybe_unused]] const rclcpp::Time & time, + [[maybe_unused]] const rclcpp::Duration & period) +{ + return hardware_interface::return_type::OK; +} + + +hardware_interface::return_type LittlebotHardwareComponent::write( + [[maybe_unused]] const rclcpp::Time & time, + [[maybe_unused]] const rclcpp::Duration & period) +{ + return hardware_interface::return_type::OK; +} } // namespace littlebot_base diff --git a/littlebot_base/src/littlebot_protocol.proto b/littlebot_base/src/littlebot_protocol.proto new file mode 100644 index 0000000..7786f3d --- /dev/null +++ b/littlebot_base/src/littlebot_protocol.proto @@ -0,0 +1,23 @@ +syntax = "proto3"; + +// Not necessary for Python but should still be declared to avoid name collisions +// in the Protocol Buffers namespace and non-Python languages +package protoblog; + +// Style guide prefers prefixing enum values instead of surrounding +// with an enclosing message +enum MotorSide { + LEFT = 0; + RIGHT = 1; +} + +message LittlebotProtocol { + message MotorInterface { + bool side = 1; + float status_velocity = 2; + float status_position = 3; + float command_velocity = 4; + } + + repeated MotorInterface motor_interface = 3; +}