]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
update proto messages
authorFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 25 Feb 2020 09:51:41 +0000 (10:51 +0100)
committerFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 25 Feb 2020 09:51:41 +0000 (10:51 +0100)
12 files changed:
.gitignore
otto_controller/Core/Inc/otto_communication.pb.h
otto_controller/Core/Src/main.cpp
otto_controller/Core/Src/otto_communication.pb.c
utils/catkin_ws/src/joypad_bridge/scripts/otto_communication_pb2.py
utils/catkin_ws/src/joypad_bridge/scripts/otto_communication_pb2.pyc [deleted file]
utils/catkin_ws/src/joypad_bridge/scripts/serial_receiver.py
utils/protobuf_messages/otto_communication.pb [deleted file]
utils/protobuf_messages/otto_communication.pb.c [deleted file]
utils/protobuf_messages/otto_communication.pb.h [deleted file]
utils/protobuf_messages/otto_communication.proto
utils/protobuf_messages/otto_communication_pb2.py [deleted file]

index 3b16db888f70bbb1325edd6f193088abbc30dcb0..6bd615f48b78990cedb61523e4f07413ba2083e7 100644 (file)
@@ -68,3 +68,5 @@ lib/
 msg_gen/
 srv_gen/
 
+#Py cache
+*.pyc
index 8fca389ceb9a06cf74e75bbb73bc80f9b2223de1..0822d214805c948ac770177cdcff170cedff1afb 100644 (file)
 extern "C" {
 #endif
 
-/* Enum definitions */
-typedef enum _StatusMessage_Status {
-    StatusMessage_Status_UNKNOWN = 0,
-    StatusMessage_Status_WAITING_CONFIG = 1,
-    StatusMessage_Status_READY = 2,
-    StatusMessage_Status_RUNNING = 3,
-    StatusMessage_Status_H_BRIDGE_FAULT_1 = 4,
-    StatusMessage_Status_H_BRIDGE_FAULT_2 = 5,
-    StatusMessage_Status_UNKNOWN_ERROR = 6
-} StatusMessage_Status;
-
 /* Struct definitions */
 typedef struct _ConfigCommand {
     float left_kp;
@@ -44,8 +33,8 @@ typedef struct _ConfigCommand {
 typedef struct _StatusMessage {
     float linear_velocity;
     float angular_velocity;
-    uint64_t delta_millis;
-    StatusMessage_Status status;
+    uint32_t delta_millis;
+    uint32_t status;
 } StatusMessage;
 
 typedef struct _VelocityCommand {
@@ -54,17 +43,11 @@ typedef struct _VelocityCommand {
 } VelocityCommand;
 
 
-/* Helper constants for enums */
-#define _StatusMessage_Status_MIN StatusMessage_Status_UNKNOWN
-#define _StatusMessage_Status_MAX StatusMessage_Status_UNKNOWN_ERROR
-#define _StatusMessage_Status_ARRAYSIZE ((StatusMessage_Status)(StatusMessage_Status_UNKNOWN_ERROR+1))
-
-
 /* Initializer values for message structs */
-#define StatusMessage_init_default               {0, 0, 0, _StatusMessage_Status_MIN}
+#define StatusMessage_init_default               {0, 0, 0, 0}
 #define ConfigCommand_init_default               {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #define VelocityCommand_init_default             {0, 0}
-#define StatusMessage_init_zero                  {0, 0, 0, _StatusMessage_Status_MIN}
+#define StatusMessage_init_zero                  {0, 0, 0, 0}
 #define ConfigCommand_init_zero                  {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #define VelocityCommand_init_zero                {0, 0}
 
@@ -93,8 +76,8 @@ typedef struct _VelocityCommand {
 #define StatusMessage_FIELDLIST(X, a) \
 X(a, STATIC,   REQUIRED, FLOAT,    linear_velocity,   1) \
 X(a, STATIC,   REQUIRED, FLOAT,    angular_velocity,   2) \
-X(a, STATIC,   REQUIRED, FIXED64,  delta_millis,      3) \
-X(a, STATIC,   REQUIRED, UENUM,    status,            4)
+X(a, STATIC,   REQUIRED, FIXED32,  delta_millis,      3) \
+X(a, STATIC,   REQUIRED, FIXED32,  status,            4)
 #define StatusMessage_CALLBACK NULL
 #define StatusMessage_DEFAULT NULL
 
@@ -131,7 +114,7 @@ extern const pb_msgdesc_t VelocityCommand_msg;
 #define VelocityCommand_fields &VelocityCommand_msg
 
 /* Maximum encoded size of messages (where known) */
-#define StatusMessage_size                       21
+#define StatusMessage_size                       20
 #define ConfigCommand_size                       65
 #define VelocityCommand_size                     10
 
index bd62e030fca986a3d72393a2361cfd10e82892db..8b2da4e416bed450367669ef78de022a0c678807 100644 (file)
@@ -205,27 +205,14 @@ int main(void)
   vel_cmd = VelocityCommand_init_zero;\r
   status_msg = StatusMessage_init_zero;\r
 \r
-  in_pb_stream = pb_istream_from_buffer(proto_buffer_rx,\r
-                                        sizeof(proto_buffer_rx));\r
-  out_pb_stream = pb_ostream_from_buffer(proto_buffer_tx,\r
-                                         sizeof(proto_buffer_tx));\r
-\r
-  pb_encode(&out_pb_stream, VelocityCommand_fields, &vel_cmd);\r
-  velocity_cmd_length = out_pb_stream.bytes_written;\r
-\r
-  pb_encode(&out_pb_stream, StatusMessage_fields, &status_msg);\r
-  status_msg_length = out_pb_stream.bytes_written;\r
-\r
   //Enables TIM6 interrupt (used for periodic transmission of the odometry)\r
   HAL_TIM_Base_Start_IT(&htim6);\r
 \r
   //Enables UART RX interrupt\r
   HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx,\r
-                       velocity_cmd_length);\r
+                       VelocityCommand_size);\r
 \r
   /* USER CODE END 2 */\r
\r
\r
 \r
   /* Infinite loop */\r
   /* USER CODE BEGIN WHILE */\r
@@ -338,11 +325,11 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
     status_msg.delta_millis = current_tx_millis - previous_tx_millis;\r
     previous_tx_millis = current_tx_millis;\r
 \r
-    status_msg.status = StatusMessage_Status_RUNNING;\r
+    status_msg.status = 3;\r
 \r
     pb_encode(&stream, StatusMessage_fields, &status_msg);\r
 \r
-    HAL_UART_Transmit_DMA(&huart6,(uint8_t*) &proto_buffer_tx, status_msg_length);\r
+    HAL_UART_Transmit_DMA(&huart6,(uint8_t*) &proto_buffer_tx, StatusMessage_size);\r
   }\r
 }\r
 \r
@@ -362,7 +349,7 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) {
   float angular_velocity;\r
 \r
   pb_istream_t stream = pb_istream_from_buffer(proto_buffer_rx,\r
-                                               velocity_cmd_length);\r
+                                               VelocityCommand_size);\r
 \r
   bool status = pb_decode(&stream, VelocityCommand_fields, &vel_cmd);\r
 \r
@@ -389,7 +376,7 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) {
   }\r
 \r
   HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx,\r
-                       velocity_cmd_length);\r
+                       VelocityCommand_size);\r
 \r
   end_time = HAL_GetTick();\r
   time_diff = end_time - start_time;\r
index 9a82e27dce96e464c57da80c9c09c560ee41858f..79705b777766d5a3aac1dfd6afbd0842ea45985f 100644 (file)
@@ -16,4 +16,3 @@ PB_BIND(VelocityCommand, VelocityCommand, AUTO)
 
 
 
-
index fe68e9fad3bba8885edc00972eae487732d0538b..340dd63579dff5ea1ae9688679940eb7ae3c99ec 100644 (file)
@@ -19,54 +19,12 @@ DESCRIPTOR = _descriptor.FileDescriptor(
   name='otto_communication.proto',
   package='',
   syntax='proto2',
-  serialized_pb=_b('\n\x18otto_communication.proto\"\x82\x02\n\rStatusMessage\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02\x12\x14\n\x0c\x64\x65lta_millis\x18\x03 \x02(\x06\x12%\n\x06status\x18\x04 \x02(\x0e\x32\x15.StatusMessage.Status\"\x80\x01\n\x06Status\x12\x0b\n\x07UNKNOWN\x10\x00\x12\x12\n\x0eWAITING_CONFIG\x10\x01\x12\t\n\x05READY\x10\x02\x12\x0b\n\x07RUNNING\x10\x03\x12\x14\n\x10H_BRIDGE_FAULT_1\x10\x04\x12\x14\n\x10H_BRIDGE_FAULT_2\x10\x05\x12\x11\n\rUNKNOWN_ERROR\x10\x06\"\xa3\x02\n\rConfigCommand\x12\x0f\n\x07left_kp\x18\x01 \x02(\x02\x12\x0f\n\x07left_ki\x18\x02 \x02(\x02\x12\x0f\n\x07left_kd\x18\x03 \x02(\x02\x12\x10\n\x08right_kp\x18\x04 \x02(\x02\x12\x10\n\x08right_ki\x18\x05 \x02(\x02\x12\x10\n\x08right_kd\x18\x06 \x02(\x02\x12\x10\n\x08\x63ross_kp\x18\x07 \x02(\x02\x12\x10\n\x08\x63ross_ki\x18\x08 \x02(\x02\x12\x10\n\x08\x63ross_kd\x18\t \x02(\x02\x12\x10\n\x08\x62\x61seline\x18\n \x02(\x02\x12\x1c\n\x14ticks_per_revolution\x18\x0b \x02(\x07\x12!\n\x19right_wheel_circumference\x18\x0c \x02(\x02\x12 \n\x18left_wheel_circumference\x18\r \x02(\x02\"D\n\x0fVelocityCommand\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02')
+  serialized_pb=_b('\n\x18otto_communication.proto\"h\n\rStatusMessage\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02\x12\x14\n\x0c\x64\x65lta_millis\x18\x03 \x02(\x07\x12\x0e\n\x06status\x18\x04 \x02(\x07\"\xa3\x02\n\rConfigCommand\x12\x0f\n\x07left_kp\x18\x01 \x02(\x02\x12\x0f\n\x07left_ki\x18\x02 \x02(\x02\x12\x0f\n\x07left_kd\x18\x03 \x02(\x02\x12\x10\n\x08right_kp\x18\x04 \x02(\x02\x12\x10\n\x08right_ki\x18\x05 \x02(\x02\x12\x10\n\x08right_kd\x18\x06 \x02(\x02\x12\x10\n\x08\x63ross_kp\x18\x07 \x02(\x02\x12\x10\n\x08\x63ross_ki\x18\x08 \x02(\x02\x12\x10\n\x08\x63ross_kd\x18\t \x02(\x02\x12\x10\n\x08\x62\x61seline\x18\n \x02(\x02\x12\x1c\n\x14ticks_per_revolution\x18\x0b \x02(\x07\x12!\n\x19right_wheel_circumference\x18\x0c \x02(\x02\x12 \n\x18left_wheel_circumference\x18\r \x02(\x02\"D\n\x0fVelocityCommand\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02')
 )
 _sym_db.RegisterFileDescriptor(DESCRIPTOR)
 
 
 
-_STATUSMESSAGE_STATUS = _descriptor.EnumDescriptor(
-  name='Status',
-  full_name='StatusMessage.Status',
-  filename=None,
-  file=DESCRIPTOR,
-  values=[
-    _descriptor.EnumValueDescriptor(
-      name='UNKNOWN', index=0, number=0,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='WAITING_CONFIG', index=1, number=1,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='READY', index=2, number=2,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='RUNNING', index=3, number=3,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='H_BRIDGE_FAULT_1', index=4, number=4,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='H_BRIDGE_FAULT_2', index=5, number=5,
-      options=None,
-      type=None),
-    _descriptor.EnumValueDescriptor(
-      name='UNKNOWN_ERROR', index=6, number=6,
-      options=None,
-      type=None),
-  ],
-  containing_type=None,
-  options=None,
-  serialized_start=159,
-  serialized_end=287,
-)
-_sym_db.RegisterEnumDescriptor(_STATUSMESSAGE_STATUS)
-
 
 _STATUSMESSAGE = _descriptor.Descriptor(
   name='StatusMessage',
@@ -91,14 +49,14 @@ _STATUSMESSAGE = _descriptor.Descriptor(
       options=None),
     _descriptor.FieldDescriptor(
       name='delta_millis', full_name='StatusMessage.delta_millis', index=2,
-      number=3, type=6, cpp_type=4, label=2,
+      number=3, type=7, cpp_type=3, label=2,
       has_default_value=False, default_value=0,
       message_type=None, enum_type=None, containing_type=None,
       is_extension=False, extension_scope=None,
       options=None),
     _descriptor.FieldDescriptor(
       name='status', full_name='StatusMessage.status', index=3,
-      number=4, type=14, cpp_type=8, label=2,
+      number=4, type=7, cpp_type=3, label=2,
       has_default_value=False, default_value=0,
       message_type=None, enum_type=None, containing_type=None,
       is_extension=False, extension_scope=None,
@@ -108,7 +66,6 @@ _STATUSMESSAGE = _descriptor.Descriptor(
   ],
   nested_types=[],
   enum_types=[
-    _STATUSMESSAGE_STATUS,
   ],
   options=None,
   is_extendable=False,
@@ -116,8 +73,8 @@ _STATUSMESSAGE = _descriptor.Descriptor(
   extension_ranges=[],
   oneofs=[
   ],
-  serialized_start=29,
-  serialized_end=287,
+  serialized_start=28,
+  serialized_end=132,
 )
 
 
@@ -231,8 +188,8 @@ _CONFIGCOMMAND = _descriptor.Descriptor(
   extension_ranges=[],
   oneofs=[
   ],
-  serialized_start=290,
-  serialized_end=581,
+  serialized_start=135,
+  serialized_end=426,
 )
 
 
@@ -269,12 +226,10 @@ _VELOCITYCOMMAND = _descriptor.Descriptor(
   extension_ranges=[],
   oneofs=[
   ],
-  serialized_start=583,
-  serialized_end=651,
+  serialized_start=428,
+  serialized_end=496,
 )
 
-_STATUSMESSAGE.fields_by_name['status'].enum_type = _STATUSMESSAGE_STATUS
-_STATUSMESSAGE_STATUS.containing_type = _STATUSMESSAGE
 DESCRIPTOR.message_types_by_name['StatusMessage'] = _STATUSMESSAGE
 DESCRIPTOR.message_types_by_name['ConfigCommand'] = _CONFIGCOMMAND
 DESCRIPTOR.message_types_by_name['VelocityCommand'] = _VELOCITYCOMMAND
diff --git a/utils/catkin_ws/src/joypad_bridge/scripts/otto_communication_pb2.pyc b/utils/catkin_ws/src/joypad_bridge/scripts/otto_communication_pb2.pyc
deleted file mode 100644 (file)
index acdac7a..0000000
Binary files a/utils/catkin_ws/src/joypad_bridge/scripts/otto_communication_pb2.pyc and /dev/null differ
index b0883477e98419071dff7749a9d4ae8e8d2670ff..196f594e28d28765fdc7be921684ecb23420a9ea 100755 (executable)
@@ -39,10 +39,10 @@ def serial_receiver():
     odom_broadcaster = tf.TransformBroadcaster()
 
     otto_status = otto_communication_pb2.StatusMessage()
-    otto_status.linear_velocity = 7
-    otto_status.angular_velocity = 7
-    otto_status.delta_millis = 7
-    otto_status.status = otto_communication_pb2.StatusMessage.Status.RUNNING
+    otto_status.linear_velocity = 0
+    otto_status.angular_velocity = 0
+    otto_status.delta_millis = 0
+    otto_status.status = 0
 
     encoded_buffer = otto_status.SerializeToString()
 
@@ -56,14 +56,14 @@ def serial_receiver():
     radius = 0;
 
     while (not rospy.is_shutdown()):
-        start = datetime.datetime.now()
-        encoded_buffer = ser.read(31)
+        ser.reset_input_buffer()
+        encoded_buffer = ser.read(status_length)
         
         try:
             otto_status.ParseFromString(encoded_buffer)
             print(otto_status)
             
-            if (otto_status.status == otto_communication_pb2.StatusMessage.Status.RUNNING):
+            if (otto_status.status == 3):
                 lin_vel = otto_status.linear_velocity
                 ang_vel = otto_status.angular_velocity
                 d_time = otto_status.delta_millis
@@ -110,11 +110,6 @@ def serial_receiver():
         except DecodeError:
             print("Decode Error")
             ser.reset_input_buffer()
-            
-        end = datetime.datetime.now()
-        delta = end - start
-        delta = (delta.total_seconds()*1000)
-        print(delta)
 
 
 if __name__ == '__main__':
diff --git a/utils/protobuf_messages/otto_communication.pb b/utils/protobuf_messages/otto_communication.pb
deleted file mode 100644 (file)
index 435262e..0000000
+++ /dev/null
@@ -1,26 +0,0 @@
-
\ 5
-\18otto_communication.proto"\9e\ 1
-\rStatusMessage\12'
-\ flinear_velocity\18\ 1 \ 2(\ 2R\ elinearVelocity\12)
-\10angular_velocity\18\ 2 \ 2(\ 2R\ fangularVelocity\12!
-\fdelta_millis\18\ 3 \ 2(\aR\vdeltaMillis\12\16
-\ 6status\18\ 4 \ 2(\aR\ 6status"À\ 3
-\rConfigCommand\12\17
-\aleft_kp\18\ 1 \ 2(\ 2R\ 6leftKp\12\17
-\aleft_ki\18\ 2 \ 2(\ 2R\ 6leftKi\12\17
-\aleft_kd\18\ 3 \ 2(\ 2R\ 6leftKd\12\19
-\bright_kp\18\ 4 \ 2(\ 2R\arightKp\12\19
-\bright_ki\18\ 5 \ 2(\ 2R\arightKi\12\19
-\bright_kd\18\ 6 \ 2(\ 2R\arightKd\12\19
-\bcross_kp\18\a \ 2(\ 2R\acrossKp\12\19
-\bcross_ki\18\b \ 2(\ 2R\acrossKi\12\19
-\bcross_kd\18      \ 2(\ 2R\acrossKd\12\1a
-\bbaseline\18
\ 2(\ 2R\bbaseline\120
-\14ticks_per_revolution\18\v \ 2(\aR\12ticksPerRevolution\12:
-\19right_wheel_circumference\18\f \ 2(\ 2R\17rightWheelCircumference\128
-\18left_wheel_circumference\18\r \ 2(\ 2R\16leftWheelCircumference"e
-\ fVelocityCommand\12'
-\ flinear_velocity\18\ 1 \ 2(\ 2R\ elinearVelocity\12)
-\10angular_velocity\18\ 2 \ 2(\ 2R\ fangularVelocity
\ No newline at end of file
diff --git a/utils/protobuf_messages/otto_communication.pb.c b/utils/protobuf_messages/otto_communication.pb.c
deleted file mode 100644 (file)
index 79705b7..0000000
+++ /dev/null
@@ -1,18 +0,0 @@
-/* Automatically generated nanopb constant definitions */
-/* Generated by 0.4.1-dev */
-
-#include "otto_communication.pb.h"
-#if PB_PROTO_HEADER_VERSION != 40
-#error Regenerate this file with the current version of nanopb generator.
-#endif
-
-PB_BIND(StatusMessage, StatusMessage, AUTO)
-
-
-PB_BIND(ConfigCommand, ConfigCommand, AUTO)
-
-
-PB_BIND(VelocityCommand, VelocityCommand, AUTO)
-
-
-
diff --git a/utils/protobuf_messages/otto_communication.pb.h b/utils/protobuf_messages/otto_communication.pb.h
deleted file mode 100644 (file)
index 0822d21..0000000
+++ /dev/null
@@ -1,125 +0,0 @@
-/* Automatically generated nanopb header */
-/* Generated by 0.4.1-dev */
-
-#ifndef PB_OTTO_COMMUNICATION_PB_H_INCLUDED
-#define PB_OTTO_COMMUNICATION_PB_H_INCLUDED
-#include <pb.h>
-
-#if PB_PROTO_HEADER_VERSION != 40
-#error Regenerate this file with the current version of nanopb generator.
-#endif
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/* Struct definitions */
-typedef struct _ConfigCommand {
-    float left_kp;
-    float left_ki;
-    float left_kd;
-    float right_kp;
-    float right_ki;
-    float right_kd;
-    float cross_kp;
-    float cross_ki;
-    float cross_kd;
-    float baseline;
-    uint32_t ticks_per_revolution;
-    float right_wheel_circumference;
-    float left_wheel_circumference;
-} ConfigCommand;
-
-typedef struct _StatusMessage {
-    float linear_velocity;
-    float angular_velocity;
-    uint32_t delta_millis;
-    uint32_t status;
-} StatusMessage;
-
-typedef struct _VelocityCommand {
-    float linear_velocity;
-    float angular_velocity;
-} VelocityCommand;
-
-
-/* Initializer values for message structs */
-#define StatusMessage_init_default               {0, 0, 0, 0}
-#define ConfigCommand_init_default               {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#define VelocityCommand_init_default             {0, 0}
-#define StatusMessage_init_zero                  {0, 0, 0, 0}
-#define ConfigCommand_init_zero                  {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#define VelocityCommand_init_zero                {0, 0}
-
-/* Field tags (for use in manual encoding/decoding) */
-#define ConfigCommand_left_kp_tag                1
-#define ConfigCommand_left_ki_tag                2
-#define ConfigCommand_left_kd_tag                3
-#define ConfigCommand_right_kp_tag               4
-#define ConfigCommand_right_ki_tag               5
-#define ConfigCommand_right_kd_tag               6
-#define ConfigCommand_cross_kp_tag               7
-#define ConfigCommand_cross_ki_tag               8
-#define ConfigCommand_cross_kd_tag               9
-#define ConfigCommand_baseline_tag               10
-#define ConfigCommand_ticks_per_revolution_tag   11
-#define ConfigCommand_right_wheel_circumference_tag 12
-#define ConfigCommand_left_wheel_circumference_tag 13
-#define StatusMessage_linear_velocity_tag        1
-#define StatusMessage_angular_velocity_tag       2
-#define StatusMessage_delta_millis_tag           3
-#define StatusMessage_status_tag                 4
-#define VelocityCommand_linear_velocity_tag      1
-#define VelocityCommand_angular_velocity_tag     2
-
-/* Struct field encoding specification for nanopb */
-#define StatusMessage_FIELDLIST(X, a) \
-X(a, STATIC,   REQUIRED, FLOAT,    linear_velocity,   1) \
-X(a, STATIC,   REQUIRED, FLOAT,    angular_velocity,   2) \
-X(a, STATIC,   REQUIRED, FIXED32,  delta_millis,      3) \
-X(a, STATIC,   REQUIRED, FIXED32,  status,            4)
-#define StatusMessage_CALLBACK NULL
-#define StatusMessage_DEFAULT NULL
-
-#define ConfigCommand_FIELDLIST(X, a) \
-X(a, STATIC,   REQUIRED, FLOAT,    left_kp,           1) \
-X(a, STATIC,   REQUIRED, FLOAT,    left_ki,           2) \
-X(a, STATIC,   REQUIRED, FLOAT,    left_kd,           3) \
-X(a, STATIC,   REQUIRED, FLOAT,    right_kp,          4) \
-X(a, STATIC,   REQUIRED, FLOAT,    right_ki,          5) \
-X(a, STATIC,   REQUIRED, FLOAT,    right_kd,          6) \
-X(a, STATIC,   REQUIRED, FLOAT,    cross_kp,          7) \
-X(a, STATIC,   REQUIRED, FLOAT,    cross_ki,          8) \
-X(a, STATIC,   REQUIRED, FLOAT,    cross_kd,          9) \
-X(a, STATIC,   REQUIRED, FLOAT,    baseline,         10) \
-X(a, STATIC,   REQUIRED, FIXED32,  ticks_per_revolution,  11) \
-X(a, STATIC,   REQUIRED, FLOAT,    right_wheel_circumference,  12) \
-X(a, STATIC,   REQUIRED, FLOAT,    left_wheel_circumference,  13)
-#define ConfigCommand_CALLBACK NULL
-#define ConfigCommand_DEFAULT NULL
-
-#define VelocityCommand_FIELDLIST(X, a) \
-X(a, STATIC,   REQUIRED, FLOAT,    linear_velocity,   1) \
-X(a, STATIC,   REQUIRED, FLOAT,    angular_velocity,   2)
-#define VelocityCommand_CALLBACK NULL
-#define VelocityCommand_DEFAULT NULL
-
-extern const pb_msgdesc_t StatusMessage_msg;
-extern const pb_msgdesc_t ConfigCommand_msg;
-extern const pb_msgdesc_t VelocityCommand_msg;
-
-/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
-#define StatusMessage_fields &StatusMessage_msg
-#define ConfigCommand_fields &ConfigCommand_msg
-#define VelocityCommand_fields &VelocityCommand_msg
-
-/* Maximum encoded size of messages (where known) */
-#define StatusMessage_size                       20
-#define ConfigCommand_size                       65
-#define VelocityCommand_size                     10
-
-#ifdef __cplusplus
-} /* extern "C" */
-#endif
-
-#endif
index 7568b4c15644914f396ee17510c7d6ef06006839..1e865acc7f561894fd799e861fb3072658394ba2 100644 (file)
@@ -21,6 +21,7 @@ message StatusMessage {
   required fixed32 status = 4;
 }
 
+// Message sent from the computer to ST board
 message ConfigCommand {
   required float left_kp = 1;
   required float left_ki = 2;
@@ -41,6 +42,7 @@ message ConfigCommand {
   required float left_wheel_circumference = 13;
 }
 
+// Message sent from the computer to ST board
 message VelocityCommand {
   required float linear_velocity = 1;
   required float angular_velocity = 2;
diff --git a/utils/protobuf_messages/otto_communication_pb2.py b/utils/protobuf_messages/otto_communication_pb2.py
deleted file mode 100644 (file)
index 340dd63..0000000
+++ /dev/null
@@ -1,259 +0,0 @@
-# Generated by the protocol buffer compiler.  DO NOT EDIT!
-# source: otto_communication.proto
-
-import sys
-_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
-from google.protobuf import descriptor as _descriptor
-from google.protobuf import message as _message
-from google.protobuf import reflection as _reflection
-from google.protobuf import symbol_database as _symbol_database
-from google.protobuf import descriptor_pb2
-# @@protoc_insertion_point(imports)
-
-_sym_db = _symbol_database.Default()
-
-
-
-
-DESCRIPTOR = _descriptor.FileDescriptor(
-  name='otto_communication.proto',
-  package='',
-  syntax='proto2',
-  serialized_pb=_b('\n\x18otto_communication.proto\"h\n\rStatusMessage\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02\x12\x14\n\x0c\x64\x65lta_millis\x18\x03 \x02(\x07\x12\x0e\n\x06status\x18\x04 \x02(\x07\"\xa3\x02\n\rConfigCommand\x12\x0f\n\x07left_kp\x18\x01 \x02(\x02\x12\x0f\n\x07left_ki\x18\x02 \x02(\x02\x12\x0f\n\x07left_kd\x18\x03 \x02(\x02\x12\x10\n\x08right_kp\x18\x04 \x02(\x02\x12\x10\n\x08right_ki\x18\x05 \x02(\x02\x12\x10\n\x08right_kd\x18\x06 \x02(\x02\x12\x10\n\x08\x63ross_kp\x18\x07 \x02(\x02\x12\x10\n\x08\x63ross_ki\x18\x08 \x02(\x02\x12\x10\n\x08\x63ross_kd\x18\t \x02(\x02\x12\x10\n\x08\x62\x61seline\x18\n \x02(\x02\x12\x1c\n\x14ticks_per_revolution\x18\x0b \x02(\x07\x12!\n\x19right_wheel_circumference\x18\x0c \x02(\x02\x12 \n\x18left_wheel_circumference\x18\r \x02(\x02\"D\n\x0fVelocityCommand\x12\x17\n\x0flinear_velocity\x18\x01 \x02(\x02\x12\x18\n\x10\x61ngular_velocity\x18\x02 \x02(\x02')
-)
-_sym_db.RegisterFileDescriptor(DESCRIPTOR)
-
-
-
-
-_STATUSMESSAGE = _descriptor.Descriptor(
-  name='StatusMessage',
-  full_name='StatusMessage',
-  filename=None,
-  file=DESCRIPTOR,
-  containing_type=None,
-  fields=[
-    _descriptor.FieldDescriptor(
-      name='linear_velocity', full_name='StatusMessage.linear_velocity', index=0,
-      number=1, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='angular_velocity', full_name='StatusMessage.angular_velocity', index=1,
-      number=2, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='delta_millis', full_name='StatusMessage.delta_millis', index=2,
-      number=3, type=7, cpp_type=3, label=2,
-      has_default_value=False, default_value=0,
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='status', full_name='StatusMessage.status', index=3,
-      number=4, type=7, cpp_type=3, label=2,
-      has_default_value=False, default_value=0,
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-  ],
-  extensions=[
-  ],
-  nested_types=[],
-  enum_types=[
-  ],
-  options=None,
-  is_extendable=False,
-  syntax='proto2',
-  extension_ranges=[],
-  oneofs=[
-  ],
-  serialized_start=28,
-  serialized_end=132,
-)
-
-
-_CONFIGCOMMAND = _descriptor.Descriptor(
-  name='ConfigCommand',
-  full_name='ConfigCommand',
-  filename=None,
-  file=DESCRIPTOR,
-  containing_type=None,
-  fields=[
-    _descriptor.FieldDescriptor(
-      name='left_kp', full_name='ConfigCommand.left_kp', index=0,
-      number=1, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='left_ki', full_name='ConfigCommand.left_ki', index=1,
-      number=2, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='left_kd', full_name='ConfigCommand.left_kd', index=2,
-      number=3, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='right_kp', full_name='ConfigCommand.right_kp', index=3,
-      number=4, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='right_ki', full_name='ConfigCommand.right_ki', index=4,
-      number=5, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='right_kd', full_name='ConfigCommand.right_kd', index=5,
-      number=6, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='cross_kp', full_name='ConfigCommand.cross_kp', index=6,
-      number=7, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='cross_ki', full_name='ConfigCommand.cross_ki', index=7,
-      number=8, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='cross_kd', full_name='ConfigCommand.cross_kd', index=8,
-      number=9, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='baseline', full_name='ConfigCommand.baseline', index=9,
-      number=10, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='ticks_per_revolution', full_name='ConfigCommand.ticks_per_revolution', index=10,
-      number=11, type=7, cpp_type=3, label=2,
-      has_default_value=False, default_value=0,
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='right_wheel_circumference', full_name='ConfigCommand.right_wheel_circumference', index=11,
-      number=12, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='left_wheel_circumference', full_name='ConfigCommand.left_wheel_circumference', index=12,
-      number=13, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-  ],
-  extensions=[
-  ],
-  nested_types=[],
-  enum_types=[
-  ],
-  options=None,
-  is_extendable=False,
-  syntax='proto2',
-  extension_ranges=[],
-  oneofs=[
-  ],
-  serialized_start=135,
-  serialized_end=426,
-)
-
-
-_VELOCITYCOMMAND = _descriptor.Descriptor(
-  name='VelocityCommand',
-  full_name='VelocityCommand',
-  filename=None,
-  file=DESCRIPTOR,
-  containing_type=None,
-  fields=[
-    _descriptor.FieldDescriptor(
-      name='linear_velocity', full_name='VelocityCommand.linear_velocity', index=0,
-      number=1, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-    _descriptor.FieldDescriptor(
-      name='angular_velocity', full_name='VelocityCommand.angular_velocity', index=1,
-      number=2, type=2, cpp_type=6, label=2,
-      has_default_value=False, default_value=float(0),
-      message_type=None, enum_type=None, containing_type=None,
-      is_extension=False, extension_scope=None,
-      options=None),
-  ],
-  extensions=[
-  ],
-  nested_types=[],
-  enum_types=[
-  ],
-  options=None,
-  is_extendable=False,
-  syntax='proto2',
-  extension_ranges=[],
-  oneofs=[
-  ],
-  serialized_start=428,
-  serialized_end=496,
-)
-
-DESCRIPTOR.message_types_by_name['StatusMessage'] = _STATUSMESSAGE
-DESCRIPTOR.message_types_by_name['ConfigCommand'] = _CONFIGCOMMAND
-DESCRIPTOR.message_types_by_name['VelocityCommand'] = _VELOCITYCOMMAND
-
-StatusMessage = _reflection.GeneratedProtocolMessageType('StatusMessage', (_message.Message,), dict(
-  DESCRIPTOR = _STATUSMESSAGE,
-  __module__ = 'otto_communication_pb2'
-  # @@protoc_insertion_point(class_scope:StatusMessage)
-  ))
-_sym_db.RegisterMessage(StatusMessage)
-
-ConfigCommand = _reflection.GeneratedProtocolMessageType('ConfigCommand', (_message.Message,), dict(
-  DESCRIPTOR = _CONFIGCOMMAND,
-  __module__ = 'otto_communication_pb2'
-  # @@protoc_insertion_point(class_scope:ConfigCommand)
-  ))
-_sym_db.RegisterMessage(ConfigCommand)
-
-VelocityCommand = _reflection.GeneratedProtocolMessageType('VelocityCommand', (_message.Message,), dict(
-  DESCRIPTOR = _VELOCITYCOMMAND,
-  __module__ = 'otto_communication_pb2'
-  # @@protoc_insertion_point(class_scope:VelocityCommand)
-  ))
-_sym_db.RegisterMessage(VelocityCommand)
-
-
-# @@protoc_insertion_point(module_scope)