aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDimitri Sokolyuk <demon@dim13.org>2017-12-11 21:49:58 +0100
committerDimitri Sokolyuk <demon@dim13.org>2017-12-11 21:49:58 +0100
commitb55a08cd6aba0364d8ef4c450f8aeb057bb936ee (patch)
tree80d216699a6e80badaf974650ada467241fc3651
parent7b489b6abcebff02b699cba8c956b6a582082d0d (diff)
submessages
-rw-r--r--elegoo.pb.go146
-rw-r--r--elegoo.proto18
-rw-r--r--elegoo/elegoo.ino22
-rw-r--r--elegoo/elegoo.pb.c54
-rw-r--r--elegoo/elegoo.pb.h58
5 files changed, 199 insertions, 99 deletions
diff --git a/elegoo.pb.go b/elegoo.pb.go
index fe63354..6ed63d7 100644
--- a/elegoo.pb.go
+++ b/elegoo.pb.go
@@ -8,7 +8,9 @@ It is generated from these files:
elegoo.proto
It has these top-level messages:
+ Speed
Command
+ Sensor
Events
*/
package main
@@ -28,9 +30,32 @@ var _ = math.Inf
// proto package needs to be updated.
const _ = proto.ProtoPackageIsVersion2 // please upgrade the proto package
+type Speed struct {
+ L int32 `protobuf:"zigzag32,1,opt,name=L" json:"L,omitempty"`
+ R int32 `protobuf:"zigzag32,2,opt,name=R" json:"R,omitempty"`
+}
+
+func (m *Speed) Reset() { *m = Speed{} }
+func (m *Speed) String() string { return proto.CompactTextString(m) }
+func (*Speed) ProtoMessage() {}
+func (*Speed) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{0} }
+
+func (m *Speed) GetL() int32 {
+ if m != nil {
+ return m.L
+ }
+ return 0
+}
+
+func (m *Speed) GetR() int32 {
+ if m != nil {
+ return m.R
+ }
+ return 0
+}
+
type Command struct {
- SpeedR int32 `protobuf:"zigzag32,1,opt,name=SpeedR" json:"SpeedR,omitempty"`
- SpeedL int32 `protobuf:"zigzag32,2,opt,name=SpeedL" json:"SpeedL,omitempty"`
+ Speed *Speed `protobuf:"bytes,1,opt,name=Speed" json:"Speed,omitempty"`
Stop bool `protobuf:"varint,3,opt,name=Stop" json:"Stop,omitempty"`
Direction uint32 `protobuf:"varint,4,opt,name=Direction" json:"Direction,omitempty"`
StopAfter uint32 `protobuf:"varint,5,opt,name=StopAfter" json:"StopAfter,omitempty"`
@@ -39,20 +64,13 @@ type Command struct {
func (m *Command) Reset() { *m = Command{} }
func (m *Command) String() string { return proto.CompactTextString(m) }
func (*Command) ProtoMessage() {}
-func (*Command) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{0} }
-
-func (m *Command) GetSpeedR() int32 {
- if m != nil {
- return m.SpeedR
- }
- return 0
-}
+func (*Command) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{1} }
-func (m *Command) GetSpeedL() int32 {
+func (m *Command) GetSpeed() *Speed {
if m != nil {
- return m.SpeedL
+ return m.Speed
}
- return 0
+ return nil
}
func (m *Command) GetStop() bool {
@@ -76,20 +94,50 @@ func (m *Command) GetStopAfter() uint32 {
return 0
}
+type Sensor struct {
+ R bool `protobuf:"varint,1,opt,name=R" json:"R,omitempty"`
+ C bool `protobuf:"varint,2,opt,name=C" json:"C,omitempty"`
+ L bool `protobuf:"varint,3,opt,name=L" json:"L,omitempty"`
+}
+
+func (m *Sensor) Reset() { *m = Sensor{} }
+func (m *Sensor) String() string { return proto.CompactTextString(m) }
+func (*Sensor) ProtoMessage() {}
+func (*Sensor) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{2} }
+
+func (m *Sensor) GetR() bool {
+ if m != nil {
+ return m.R
+ }
+ return false
+}
+
+func (m *Sensor) GetC() bool {
+ if m != nil {
+ return m.C
+ }
+ return false
+}
+
+func (m *Sensor) GetL() bool {
+ if m != nil {
+ return m.L
+ }
+ return false
+}
+
type Events struct {
- Distance uint32 `protobuf:"varint,1,opt,name=Distance" json:"Distance,omitempty"`
- Direction int32 `protobuf:"zigzag32,2,opt,name=Direction" json:"Direction,omitempty"`
- SensorR bool `protobuf:"varint,3,opt,name=SensorR" json:"SensorR,omitempty"`
- SensorC bool `protobuf:"varint,4,opt,name=SensorC" json:"SensorC,omitempty"`
- SensorL bool `protobuf:"varint,5,opt,name=SensorL" json:"SensorL,omitempty"`
- KeyPress uint32 `protobuf:"varint,6,opt,name=KeyPress" json:"KeyPress,omitempty"`
- Time uint32 `protobuf:"varint,7,opt,name=Time" json:"Time,omitempty"`
+ Distance uint32 `protobuf:"varint,1,opt,name=Distance" json:"Distance,omitempty"`
+ Direction int32 `protobuf:"zigzag32,2,opt,name=Direction" json:"Direction,omitempty"`
+ Sensor *Sensor `protobuf:"bytes,3,opt,name=Sensor" json:"Sensor,omitempty"`
+ KeyPress uint32 `protobuf:"varint,6,opt,name=KeyPress" json:"KeyPress,omitempty"`
+ Time uint32 `protobuf:"varint,7,opt,name=Time" json:"Time,omitempty"`
}
func (m *Events) Reset() { *m = Events{} }
func (m *Events) String() string { return proto.CompactTextString(m) }
func (*Events) ProtoMessage() {}
-func (*Events) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{1} }
+func (*Events) Descriptor() ([]byte, []int) { return fileDescriptor0, []int{3} }
func (m *Events) GetDistance() uint32 {
if m != nil {
@@ -105,25 +153,11 @@ func (m *Events) GetDirection() int32 {
return 0
}
-func (m *Events) GetSensorR() bool {
- if m != nil {
- return m.SensorR
- }
- return false
-}
-
-func (m *Events) GetSensorC() bool {
+func (m *Events) GetSensor() *Sensor {
if m != nil {
- return m.SensorC
+ return m.Sensor
}
- return false
-}
-
-func (m *Events) GetSensorL() bool {
- if m != nil {
- return m.SensorL
- }
- return false
+ return nil
}
func (m *Events) GetKeyPress() uint32 {
@@ -141,27 +175,31 @@ func (m *Events) GetTime() uint32 {
}
func init() {
+ proto.RegisterType((*Speed)(nil), "elegoo.Speed")
proto.RegisterType((*Command)(nil), "elegoo.Command")
+ proto.RegisterType((*Sensor)(nil), "elegoo.Sensor")
proto.RegisterType((*Events)(nil), "elegoo.Events")
}
func init() { proto.RegisterFile("elegoo.proto", fileDescriptor0) }
var fileDescriptor0 = []byte{
- // 236 bytes of a gzipped FileDescriptorProto
- 0x1f, 0x8b, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0xff, 0x54, 0x90, 0xb1, 0x4e, 0xc3, 0x30,
- 0x10, 0x86, 0x65, 0x08, 0x4e, 0x39, 0xd1, 0x01, 0x0f, 0xe8, 0x84, 0x18, 0xa2, 0x4e, 0x99, 0x58,
- 0x78, 0x02, 0x48, 0x99, 0xc8, 0x80, 0x1c, 0x26, 0xb6, 0xd0, 0x1e, 0xc8, 0x12, 0xf1, 0x45, 0xb6,
- 0x85, 0xc4, 0x23, 0xf0, 0x56, 0x3c, 0x1a, 0x8a, 0xdd, 0x3a, 0x61, 0xbb, 0xff, 0xff, 0x2c, 0xdd,
- 0xe7, 0x83, 0x0b, 0xfa, 0xa4, 0x0f, 0xe6, 0xdb, 0xd1, 0x71, 0x60, 0x25, 0x53, 0xda, 0xfc, 0x08,
- 0x28, 0x1b, 0x1e, 0x86, 0xde, 0xee, 0xd5, 0x15, 0xc8, 0x6e, 0x24, 0xda, 0x6b, 0x14, 0x95, 0xa8,
- 0x2f, 0xf5, 0x21, 0xe5, 0xbe, 0xc5, 0x93, 0x45, 0xdf, 0x2a, 0x05, 0x45, 0x17, 0x78, 0xc4, 0xd3,
- 0x4a, 0xd4, 0x2b, 0x1d, 0x67, 0x75, 0x03, 0xe7, 0x5b, 0xe3, 0x68, 0x17, 0x0c, 0x5b, 0x2c, 0x2a,
- 0x51, 0xaf, 0xf5, 0x5c, 0x4c, 0x74, 0x7a, 0x75, 0xff, 0x1e, 0xc8, 0xe1, 0x59, 0xa2, 0xb9, 0xd8,
- 0xfc, 0x0a, 0x90, 0x8f, 0x5f, 0x64, 0x83, 0x57, 0xd7, 0xb0, 0xda, 0x1a, 0x1f, 0x7a, 0xbb, 0xa3,
- 0x28, 0xb3, 0xd6, 0x39, 0xff, 0x5f, 0x91, 0x8c, 0x16, 0x2b, 0x10, 0xca, 0x8e, 0xac, 0x67, 0xa7,
- 0x0f, 0x5e, 0xc7, 0x38, 0x93, 0x26, 0x8a, 0x65, 0xd2, 0xcc, 0xa4, 0x8d, 0x52, 0x99, 0xb4, 0x93,
- 0xc7, 0x13, 0x7d, 0x3f, 0x3b, 0xf2, 0x1e, 0x65, 0xf2, 0x38, 0xe6, 0xe9, 0xfb, 0x2f, 0x66, 0x20,
- 0x2c, 0x63, 0x1f, 0xe7, 0x07, 0xf9, 0x5a, 0x0c, 0xbd, 0xb1, 0x6f, 0x32, 0x5e, 0xf9, 0xee, 0x2f,
- 0x00, 0x00, 0xff, 0xff, 0x84, 0x98, 0xdf, 0xe5, 0x75, 0x01, 0x00, 0x00,
+ // 268 bytes of a gzipped FileDescriptorProto
+ 0x1f, 0x8b, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0xff, 0x54, 0x91, 0xb1, 0x4e, 0x84, 0x40,
+ 0x10, 0x86, 0x33, 0xca, 0xed, 0xe1, 0xde, 0x61, 0xe2, 0x56, 0x9b, 0x8b, 0x05, 0xc1, 0xc4, 0x50,
+ 0x5d, 0x81, 0x4f, 0xa0, 0x9c, 0x95, 0x14, 0x66, 0xb0, 0xb2, 0xc3, 0xbb, 0xd1, 0x90, 0xc8, 0x2e,
+ 0x81, 0x8d, 0x89, 0x8d, 0x0f, 0xe2, 0xd3, 0x9a, 0x9d, 0x3d, 0x50, 0xbb, 0xf9, 0xfe, 0x19, 0xfe,
+ 0xf9, 0x87, 0x95, 0x6b, 0x7a, 0xa7, 0x37, 0x6b, 0xb7, 0xfd, 0x60, 0x9d, 0x55, 0x22, 0x50, 0x76,
+ 0x25, 0x17, 0x75, 0x4f, 0x74, 0x50, 0x6b, 0x09, 0x95, 0x86, 0x14, 0xf2, 0x0b, 0x84, 0xca, 0x13,
+ 0xea, 0x93, 0x40, 0x98, 0x7d, 0xc9, 0x65, 0x69, 0xbb, 0xae, 0x31, 0x07, 0x35, 0xcd, 0xf3, 0xe8,
+ 0xaa, 0x48, 0xb6, 0x47, 0x57, 0x16, 0xf1, 0xe8, 0xa5, 0x64, 0x54, 0x3b, 0xdb, 0xeb, 0xd3, 0x14,
+ 0xf2, 0x18, 0xb9, 0x56, 0x97, 0xf2, 0x6c, 0xd7, 0x0e, 0xb4, 0x77, 0xad, 0x35, 0x3a, 0x4a, 0x21,
+ 0x4f, 0xf0, 0x57, 0xf0, 0x5d, 0x3f, 0x75, 0xfb, 0xea, 0x68, 0xd0, 0x8b, 0xd0, 0x9d, 0x85, 0xac,
+ 0x90, 0xa2, 0x26, 0x33, 0xda, 0x21, 0xe4, 0x02, 0xb6, 0x05, 0xf4, 0x54, 0x72, 0xca, 0x18, 0xa1,
+ 0x0c, 0x17, 0x84, 0x95, 0x50, 0x65, 0xdf, 0x20, 0xc5, 0xfd, 0x07, 0x19, 0x37, 0xaa, 0x8d, 0x8c,
+ 0x77, 0xed, 0xe8, 0x1a, 0xb3, 0x27, 0xfe, 0x36, 0xc1, 0x99, 0xff, 0xc7, 0x0a, 0x07, 0xff, 0x89,
+ 0x75, 0x3d, 0x2d, 0x66, 0xdf, 0x55, 0x71, 0x3e, 0x9f, 0xcb, 0x2a, 0x4e, 0xb1, 0x36, 0x32, 0x7e,
+ 0xa0, 0xcf, 0xc7, 0x81, 0xc6, 0x51, 0x8b, 0xb0, 0x61, 0x62, 0xff, 0x33, 0x9e, 0xda, 0x8e, 0xf4,
+ 0x92, 0x75, 0xae, 0xef, 0xc4, 0x73, 0xd4, 0x35, 0xad, 0x79, 0x11, 0xfc, 0x18, 0x37, 0x3f, 0x01,
+ 0x00, 0x00, 0xff, 0xff, 0x90, 0x19, 0xf0, 0xc2, 0x9c, 0x01, 0x00, 0x00,
}
diff --git a/elegoo.proto b/elegoo.proto
index 16c7c5b..f553ce8 100644
--- a/elegoo.proto
+++ b/elegoo.proto
@@ -4,20 +4,28 @@ package elegoo;
option go_package = "main";
+message Speed {
+ sint32 L = 1; // -255 .. + 255
+ sint32 R = 2; // -255 .. + 255
+}
+
message Command {
- sint32 SpeedR = 1; // -255 .. +255
- sint32 SpeedL = 2; // -255 .. +255
+ Speed Speed = 1;
bool Stop = 3;
uint32 Direction = 4; // deg: 0 right .. 180 left
uint32 StopAfter = 5; // milliseconds
}
+message Sensor {
+ bool R = 1;
+ bool C = 2;
+ bool L = 3;
+}
+
message Events {
uint32 Distance = 1; // cm
sint32 Direction = 2; // deg
- bool SensorR = 3;
- bool SensorC = 4;
- bool SensorL = 5;
+ Sensor Sensor = 3;
uint32 KeyPress = 6;
uint32 Time = 7; // milliseconds
}
diff --git a/elegoo/elegoo.ino b/elegoo/elegoo.ino
index e354262..b3d1ced 100644
--- a/elegoo/elegoo.ino
+++ b/elegoo/elegoo.ino
@@ -51,16 +51,16 @@ void stop() {
}
void onPacket(const uint8_t* buf, size_t size) {
- Command cmd = Command_init_zero;
+ elegoo_Command cmd = elegoo_Command_init_zero;
pb_istream_t istream = pb_istream_from_buffer(buf, size);
- pb_decode_delimited(&istream, Command_fields, &cmd);
+ pb_decode_delimited(&istream, elegoo_Command_fields, &cmd);
- if (cmd.SpeedR > 0) {
- motorR(cmd.SpeedR);
+ if (cmd.Speed.R > 0) {
+ motorR(cmd.Speed.R);
}
- if (cmd.SpeedL > 0) {
- motorL(cmd.SpeedL);
+ if (cmd.Speed.L > 0) {
+ motorL(cmd.Speed.L);
}
if (cmd.Stop) {
stop();
@@ -76,12 +76,12 @@ void onPacket(const uint8_t* buf, size_t size) {
void events() {
uint8_t buf[64];
- Events evt = Events_init_zero;
+ elegoo_Events evt = elegoo_Events_init_zero;
evt.Distance = readDistance();
- evt.SensorR = digitalRead(SR);
- evt.SensorC = digitalRead(SC);
- evt.SensorL = digitalRead(SL);
+ evt.Sensor.R = digitalRead(SR);
+ evt.Sensor.C = digitalRead(SC);
+ evt.Sensor.L = digitalRead(SL);
if (irrecv.decode(&ir)) {
evt.KeyPress = ir.value;
@@ -92,7 +92,7 @@ void events() {
evt.Time = millis();
pb_ostream_t ostream = pb_ostream_from_buffer(buf, sizeof(buf));
- pb_encode_delimited(&ostream, Events_fields, &evt);
+ pb_encode_delimited(&ostream, elegoo_Events_fields, &evt);
serial.send(buf, ostream.bytes_written);
}
diff --git a/elegoo/elegoo.pb.c b/elegoo/elegoo.pb.c
index 1dd40bf..fad83e8 100644
--- a/elegoo/elegoo.pb.c
+++ b/elegoo/elegoo.pb.c
@@ -1,5 +1,5 @@
/* Automatically generated nanopb constant definitions */
-/* Generated by nanopb-0.3.9 at Mon Dec 11 01:03:09 2017. */
+/* Generated by nanopb-0.3.9 at Mon Dec 11 21:46:37 2017. */
#include "elegoo.pb.h"
@@ -10,25 +10,59 @@
-const pb_field_t elegoo_Command_fields[6] = {
- PB_FIELD( 1, SINT32 , SINGULAR, STATIC , FIRST, elegoo_Command, SpeedR, SpeedR, 0),
- PB_FIELD( 2, SINT32 , SINGULAR, STATIC , OTHER, elegoo_Command, SpeedL, SpeedR, 0),
- PB_FIELD( 3, BOOL , SINGULAR, STATIC , OTHER, elegoo_Command, Stop, SpeedL, 0),
+const pb_field_t elegoo_Speed_fields[3] = {
+ PB_FIELD( 1, SINT32 , SINGULAR, STATIC , FIRST, elegoo_Speed, L, L, 0),
+ PB_FIELD( 2, SINT32 , SINGULAR, STATIC , OTHER, elegoo_Speed, R, L, 0),
+ PB_LAST_FIELD
+};
+
+const pb_field_t elegoo_Command_fields[5] = {
+ PB_FIELD( 1, MESSAGE , SINGULAR, STATIC , FIRST, elegoo_Command, Speed, Speed, &elegoo_Speed_fields),
+ PB_FIELD( 3, BOOL , SINGULAR, STATIC , OTHER, elegoo_Command, Stop, Speed, 0),
PB_FIELD( 4, UINT32 , SINGULAR, STATIC , OTHER, elegoo_Command, Direction, Stop, 0),
PB_FIELD( 5, UINT32 , SINGULAR, STATIC , OTHER, elegoo_Command, StopAfter, Direction, 0),
PB_LAST_FIELD
};
-const pb_field_t elegoo_Events_fields[8] = {
+const pb_field_t elegoo_Sensor_fields[4] = {
+ PB_FIELD( 1, BOOL , SINGULAR, STATIC , FIRST, elegoo_Sensor, R, R, 0),
+ PB_FIELD( 2, BOOL , SINGULAR, STATIC , OTHER, elegoo_Sensor, C, R, 0),
+ PB_FIELD( 3, BOOL , SINGULAR, STATIC , OTHER, elegoo_Sensor, L, C, 0),
+ PB_LAST_FIELD
+};
+
+const pb_field_t elegoo_Events_fields[6] = {
PB_FIELD( 1, UINT32 , SINGULAR, STATIC , FIRST, elegoo_Events, Distance, Distance, 0),
PB_FIELD( 2, SINT32 , SINGULAR, STATIC , OTHER, elegoo_Events, Direction, Distance, 0),
- PB_FIELD( 3, BOOL , SINGULAR, STATIC , OTHER, elegoo_Events, SensorR, Direction, 0),
- PB_FIELD( 4, BOOL , SINGULAR, STATIC , OTHER, elegoo_Events, SensorC, SensorR, 0),
- PB_FIELD( 5, BOOL , SINGULAR, STATIC , OTHER, elegoo_Events, SensorL, SensorC, 0),
- PB_FIELD( 6, UINT32 , SINGULAR, STATIC , OTHER, elegoo_Events, KeyPress, SensorL, 0),
+ PB_FIELD( 3, MESSAGE , SINGULAR, STATIC , OTHER, elegoo_Events, Sensor, Direction, &elegoo_Sensor_fields),
+ PB_FIELD( 6, UINT32 , SINGULAR, STATIC , OTHER, elegoo_Events, KeyPress, Sensor, 0),
PB_FIELD( 7, UINT32 , SINGULAR, STATIC , OTHER, elegoo_Events, Time, KeyPress, 0),
PB_LAST_FIELD
};
+/* Check that field information fits in pb_field_t */
+#if !defined(PB_FIELD_32BIT)
+/* If you get an error here, it means that you need to define PB_FIELD_32BIT
+ * compile-time option. You can do that in pb.h or on compiler command line.
+ *
+ * The reason you need to do this is that some of your messages contain tag
+ * numbers or field sizes that are larger than what can fit in 8 or 16 bit
+ * field descriptors.
+ */
+PB_STATIC_ASSERT((pb_membersize(elegoo_Command, Speed) < 65536 && pb_membersize(elegoo_Events, Sensor) < 65536), YOU_MUST_DEFINE_PB_FIELD_32BIT_FOR_MESSAGES_elegoo_Speed_elegoo_Command_elegoo_Sensor_elegoo_Events)
+#endif
+
+#if !defined(PB_FIELD_16BIT) && !defined(PB_FIELD_32BIT)
+/* If you get an error here, it means that you need to define PB_FIELD_16BIT
+ * compile-time option. You can do that in pb.h or on compiler command line.
+ *
+ * The reason you need to do this is that some of your messages contain tag
+ * numbers or field sizes that are larger than what can fit in the default
+ * 8 bit descriptors.
+ */
+PB_STATIC_ASSERT((pb_membersize(elegoo_Command, Speed) < 256 && pb_membersize(elegoo_Events, Sensor) < 256), YOU_MUST_DEFINE_PB_FIELD_16BIT_FOR_MESSAGES_elegoo_Speed_elegoo_Command_elegoo_Sensor_elegoo_Events)
+#endif
+
+
/* @@protoc_insertion_point(eof) */
diff --git a/elegoo/elegoo.pb.h b/elegoo/elegoo.pb.h
index 7ba34f2..3d90f3f 100644
--- a/elegoo/elegoo.pb.h
+++ b/elegoo/elegoo.pb.h
@@ -1,5 +1,5 @@
/* Automatically generated nanopb header */
-/* Generated by nanopb-0.3.9 at Mon Dec 11 01:03:09 2017. */
+/* Generated by nanopb-0.3.9 at Mon Dec 11 21:46:37 2017. */
#ifndef PB_ELEGOO_ELEGOO_PB_H_INCLUDED
#define PB_ELEGOO_ELEGOO_PB_H_INCLUDED
@@ -15,9 +15,21 @@ extern "C" {
#endif
/* Struct definitions */
+typedef struct _elegoo_Sensor {
+ bool R;
+ bool C;
+ bool L;
+/* @@protoc_insertion_point(struct:elegoo_Sensor) */
+} elegoo_Sensor;
+
+typedef struct _elegoo_Speed {
+ int32_t L;
+ int32_t R;
+/* @@protoc_insertion_point(struct:elegoo_Speed) */
+} elegoo_Speed;
+
typedef struct _elegoo_Command {
- int32_t SpeedR;
- int32_t SpeedL;
+ elegoo_Speed Speed;
bool Stop;
uint32_t Direction;
uint32_t StopAfter;
@@ -27,9 +39,7 @@ typedef struct _elegoo_Command {
typedef struct _elegoo_Events {
uint32_t Distance;
int32_t Direction;
- bool SensorR;
- bool SensorC;
- bool SensorL;
+ elegoo_Sensor Sensor;
uint32_t KeyPress;
uint32_t Time;
/* @@protoc_insertion_point(struct:elegoo_Events) */
@@ -38,32 +48,42 @@ typedef struct _elegoo_Events {
/* Default values for struct fields */
/* Initializer values for message structs */
-#define elegoo_Command_init_default {0, 0, 0, 0, 0}
-#define elegoo_Events_init_default {0, 0, 0, 0, 0, 0, 0}
-#define elegoo_Command_init_zero {0, 0, 0, 0, 0}
-#define elegoo_Events_init_zero {0, 0, 0, 0, 0, 0, 0}
+#define elegoo_Speed_init_default {0, 0}
+#define elegoo_Command_init_default {elegoo_Speed_init_default, 0, 0, 0}
+#define elegoo_Sensor_init_default {0, 0, 0}
+#define elegoo_Events_init_default {0, 0, elegoo_Sensor_init_default, 0, 0}
+#define elegoo_Speed_init_zero {0, 0}
+#define elegoo_Command_init_zero {elegoo_Speed_init_zero, 0, 0, 0}
+#define elegoo_Sensor_init_zero {0, 0, 0}
+#define elegoo_Events_init_zero {0, 0, elegoo_Sensor_init_zero, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
-#define elegoo_Command_SpeedR_tag 1
-#define elegoo_Command_SpeedL_tag 2
+#define elegoo_Sensor_R_tag 1
+#define elegoo_Sensor_C_tag 2
+#define elegoo_Sensor_L_tag 3
+#define elegoo_Speed_L_tag 1
+#define elegoo_Speed_R_tag 2
+#define elegoo_Command_Speed_tag 1
#define elegoo_Command_Stop_tag 3
#define elegoo_Command_Direction_tag 4
#define elegoo_Command_StopAfter_tag 5
#define elegoo_Events_Distance_tag 1
#define elegoo_Events_Direction_tag 2
-#define elegoo_Events_SensorR_tag 3
-#define elegoo_Events_SensorC_tag 4
-#define elegoo_Events_SensorL_tag 5
+#define elegoo_Events_Sensor_tag 3
#define elegoo_Events_KeyPress_tag 6
#define elegoo_Events_Time_tag 7
/* Struct field encoding specification for nanopb */
-extern const pb_field_t elegoo_Command_fields[6];
-extern const pb_field_t elegoo_Events_fields[8];
+extern const pb_field_t elegoo_Speed_fields[3];
+extern const pb_field_t elegoo_Command_fields[5];
+extern const pb_field_t elegoo_Sensor_fields[4];
+extern const pb_field_t elegoo_Events_fields[6];
/* Maximum encoded size of messages (where known) */
-#define elegoo_Command_size 26
-#define elegoo_Events_size 30
+#define elegoo_Speed_size 12
+#define elegoo_Command_size 28
+#define elegoo_Sensor_size 6
+#define elegoo_Events_size 32
/* Message IDs (where set with "msgid" option) */
#ifdef PB_MSGID