start using regular protobuf instead of nanopb
Fix using full version of protobuf fix issue with lora config defaults fix a few things in cmake files fix cmake flags minor protobuf build fixes
This commit is contained in:
parent
91b017c27d
commit
611bade298
3
.gitmodules
vendored
3
.gitmodules
vendored
@ -13,3 +13,6 @@
|
|||||||
[submodule "components/minmea/minmea"]
|
[submodule "components/minmea/minmea"]
|
||||||
path = components/minmea/minmea
|
path = components/minmea/minmea
|
||||||
url = https://github.com/kosma/minmea.git
|
url = https://github.com/kosma/minmea.git
|
||||||
|
[submodule "components/protobuf/protobuf"]
|
||||||
|
path = components/protobuf/protobuf
|
||||||
|
url = https://github.com/protocolbuffers/protobuf.git
|
||||||
|
@ -9,8 +9,8 @@ function(nanopb_generate PROTO_FILE PB_OUT HDR_VAR SRC_VAR)
|
|||||||
set(${HDR_VAR} ${${HDR_VAR}} ${PROTO_HDR} PARENT_SCOPE)
|
set(${HDR_VAR} ${${HDR_VAR}} ${PROTO_HDR} PARENT_SCOPE)
|
||||||
set(${SRC_VAR} ${${SRC_VAR}} ${PROTO_SRC} PARENT_SCOPE)
|
set(${SRC_VAR} ${${SRC_VAR}} ${PROTO_SRC} PARENT_SCOPE)
|
||||||
if(NOT CMAKE_SCRIPT_MODE_FILE)
|
if(NOT CMAKE_SCRIPT_MODE_FILE)
|
||||||
add_custom_command(OUTPUT ${PROTO_HDR} ${PROTO_SRC}
|
add_custom_command(OUTPUT ${PROTO_HDR} ${PROTO_SRC}
|
||||||
COMMAND protoc
|
COMMAND protoc
|
||||||
--plugin=protoc-gen-nanopb=${NANOPB_PLUGIN}
|
--plugin=protoc-gen-nanopb=${NANOPB_PLUGIN}
|
||||||
--nanopb_out=${PB_OUT}
|
--nanopb_out=${PB_OUT}
|
||||||
--proto_path ${PROTO_FILE_DIR}
|
--proto_path ${PROTO_FILE_DIR}
|
||||||
@ -18,7 +18,6 @@ function(nanopb_generate PROTO_FILE PB_OUT HDR_VAR SRC_VAR)
|
|||||||
DEPENDS ${PROTO_FILE_PATH}
|
DEPENDS ${PROTO_FILE_PATH}
|
||||||
COMMENT "Generating nanopb sources for ${PROTO_FILE}")
|
COMMENT "Generating nanopb sources for ${PROTO_FILE}")
|
||||||
set_property(SOURCE ${PROTO_HDR} ${PROTO_SRC} PROPERTY GENERATED TRUE)
|
set_property(SOURCE ${PROTO_HDR} ${PROTO_SRC} PROPERTY GENERATED TRUE)
|
||||||
|
set_property(DIRECTORY . APPEND PROPERTY ADDITIONAL_MAKE_CLEAN_FILES ${PROTO_HDR} ${PROTO_SRC})
|
||||||
endif()
|
endif()
|
||||||
list(APPEND ADDITIONAL_MAKE_CLEAN_FILES ${PROTO_HDR} ${PROTO_SRC})
|
|
||||||
endfunction()
|
endfunction()
|
||||||
|
|
||||||
|
35
components/protobuf/CMakeLists.txt
Normal file
35
components/protobuf/CMakeLists.txt
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
set(protobuf_source_dir ${CMAKE_CURRENT_LIST_DIR}/protobuf)
|
||||||
|
|
||||||
|
set(libprotobuf_lite_files
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/arena.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/arenastring.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/extension_set.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/generated_message_util.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/io/coded_stream.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/io/zero_copy_stream.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/io/zero_copy_stream_impl_lite.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/message_lite.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/repeated_field.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/atomicops_internals_x86_gcc.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/atomicops_internals_x86_msvc.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/bytestream.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/common.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/int128.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/once.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/status.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/statusor.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/stringpiece.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/stringprintf.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/structurally_valid.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/strutil.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/stubs/time.cc
|
||||||
|
${protobuf_source_dir}/src/google/protobuf/wire_format_lite.cc
|
||||||
|
)
|
||||||
|
|
||||||
|
set(COMPONENT_SRCS ${libprotobuf_lite_files})
|
||||||
|
set(COMPONENT_ADD_INCLUDEDIRS ${protobuf_source_dir}/src)
|
||||||
|
|
||||||
|
register_component()
|
||||||
|
|
||||||
|
component_compile_options(PUBLIC -DGOOGLE_PROTOBUF_NO_RTTI -Wno-error=maybe-uninitialized
|
||||||
|
PRIVATE -DHAVE_PTHREAD)
|
22
components/protobuf/functions.cmake
Normal file
22
components/protobuf/functions.cmake
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
find_program(PROTOC protoc)
|
||||||
|
|
||||||
|
function(proto_generate_cpp PROTO_FILE PB_OUT HDR_VAR SRC_VAR)
|
||||||
|
get_filename_component(PROTO_FILE_NAME ${PROTO_FILE} NAME_WE)
|
||||||
|
get_filename_component(PROTO_FILE_PATH ${PROTO_FILE} ABSOLUTE BASE_DIR ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
get_filename_component(PROTO_FILE_DIR ${PROTO_FILE_PATH} DIRECTORY)
|
||||||
|
set(PROTO_HDR "${PB_OUT}/${PROTO_FILE_NAME}.pb.h")
|
||||||
|
set(PROTO_SRC "${PB_OUT}/${PROTO_FILE_NAME}.pb.cc")
|
||||||
|
set(${HDR_VAR} ${${HDR_VAR}} ${PROTO_HDR} PARENT_SCOPE)
|
||||||
|
set(${SRC_VAR} ${${SRC_VAR}} ${PROTO_SRC} PARENT_SCOPE)
|
||||||
|
if(NOT CMAKE_SCRIPT_MODE_FILE)
|
||||||
|
add_custom_command(OUTPUT ${PROTO_HDR} ${PROTO_SRC}
|
||||||
|
COMMAND ${PROTOC}
|
||||||
|
--cpp_out=${PB_OUT}
|
||||||
|
--proto_path ${PROTO_FILE_DIR}
|
||||||
|
${PROTO_FILE_PATH}
|
||||||
|
DEPENDS ${PROTO_FILE_PATH}
|
||||||
|
COMMENT "Generating nanopb sources for ${PROTO_FILE}")
|
||||||
|
set_property(SOURCE ${PROTO_HDR} ${PROTO_SRC} PROPERTY GENERATED TRUE)
|
||||||
|
set_property(DIRECTORY . APPEND PROPERTY ADDITIONAL_MAKE_CLEAN_FILES ${PROTO_HDR} ${PROTO_SRC})
|
||||||
|
endif()
|
||||||
|
endfunction()
|
@ -1,21 +1,25 @@
|
|||||||
include(${CMAKE_CURRENT_LIST_DIR}/../components/nanopb/functions.cmake)
|
include(${CMAKE_CURRENT_LIST_DIR}/../components/protobuf/functions.cmake)
|
||||||
|
|
||||||
set(PB_OUT ${CMAKE_CURRENT_SOURCE_DIR}/pb_out)
|
set(PB_OUT ${CMAKE_CURRENT_SOURCE_DIR}/pb_out)
|
||||||
|
|
||||||
make_directory(${PB_OUT})
|
set(COMPONENT_SRCS
|
||||||
nanopb_generate(messages.proto ${PB_OUT} PROTO_HDRS PROTO_SRCS)
|
"ugv_main.cc"
|
||||||
|
"ugv_comms.cc"
|
||||||
list(APPEND COMPONENT_SRCS "ugv_main.cc"
|
|
||||||
"ugv_comms.c"
|
|
||||||
"ugv_io.cc"
|
"ugv_io.cc"
|
||||||
"ugv_io_gps.cc"
|
"ugv_io_gps.cc"
|
||||||
"ugv_io_mpu.cc"
|
"ugv_io_mpu.cc"
|
||||||
"u8g2_esp32_hal.c"
|
"u8g2_esp32_hal.c"
|
||||||
"Print.cpp"
|
"Print.cpp"
|
||||||
${PROTO_SRCS})
|
)
|
||||||
set(COMPONENT_PRIV_INCLUDEDIRS "." ${PB_OUT})
|
set(COMPONENT_PRIV_INCLUDEDIRS "." ${PB_OUT})
|
||||||
set(COMPONENT_REQUIRES "u8g2" "sx127x_driver" "nanopb" "MPU-driver" "minmea")
|
set(COMPONENT_REQUIRES "u8g2" "sx127x_driver" "protobuf" "MPU-driver" "minmea")
|
||||||
|
|
||||||
|
proto_generate_cpp(messages.proto ${PB_OUT} PROTO_HDRS PROTO_SRCS)
|
||||||
|
list(APPEND COMPONENT_SRCS ${PROTO_SRCS} ${PROTO_HDRS})
|
||||||
|
|
||||||
register_component()
|
register_component()
|
||||||
|
|
||||||
|
make_directory(${PB_OUT})
|
||||||
|
|
||||||
component_compile_options("-Werror=incompatible-pointer-types")
|
component_compile_options("-Werror=incompatible-pointer-types")
|
||||||
|
component_compile_options(-I${PB_OUT})
|
||||||
|
@ -2,6 +2,8 @@ syntax = "proto3";
|
|||||||
|
|
||||||
package uas.ugv;
|
package uas.ugv;
|
||||||
|
|
||||||
|
option optimize_for = LITE_RUNTIME;
|
||||||
|
|
||||||
enum UGV_State {
|
enum UGV_State {
|
||||||
IDLE = 0;
|
IDLE = 0;
|
||||||
AQUIRING = 1;
|
AQUIRING = 1;
|
||||||
|
@ -2,11 +2,11 @@
|
|||||||
#include "ugv_config.h"
|
#include "ugv_config.h"
|
||||||
|
|
||||||
#include <esp_log.h>
|
#include <esp_log.h>
|
||||||
#include <pb_decode.h>
|
|
||||||
#include <pb_encode.h>
|
|
||||||
|
|
||||||
#include "messages.pb.h"
|
#include "messages.pb.h"
|
||||||
|
|
||||||
|
ugv_comms_state_t ugv_comms_state;
|
||||||
|
|
||||||
static const char *TAG = "ugv_comms";
|
static const char *TAG = "ugv_comms";
|
||||||
|
|
||||||
static void ugv_comms_task(void *arg);
|
static void ugv_comms_task(void *arg);
|
||||||
@ -15,21 +15,21 @@ static uint16_t packet_num;
|
|||||||
static void ugv_comms_task(void *arg);
|
static void ugv_comms_task(void *arg);
|
||||||
static void ugv_comms_handle_packet(ugv_comms_state_t * st,
|
static void ugv_comms_handle_packet(ugv_comms_state_t * st,
|
||||||
sx127x_rx_packet_t *rx_packet);
|
sx127x_rx_packet_t *rx_packet);
|
||||||
static void ugv_comms_handle_command(ugv_comms_state_t * st,
|
static void ugv_comms_handle_command(ugv_comms_state_t * st,
|
||||||
uas_ugv_GroundCommand *command);
|
const uas::ugv::GroundCommand *command);
|
||||||
|
|
||||||
void ugv_comms_init() {
|
void ugv_comms_init() {
|
||||||
ugv_comms_state_t *st = &ugv_comms_state;
|
ugv_comms_state_t *st = &ugv_comms_state;
|
||||||
|
|
||||||
st->mutex = xSemaphoreCreateMutex();
|
st->mutex = xSemaphoreCreateMutex();
|
||||||
|
|
||||||
sx127x_config_t lora_config = SX127X_CONFIG_DEFAULT;
|
sx127x_config_t lora_config = sx127x_config_default();
|
||||||
lora_config.sck_io_num = LORA_SCK;
|
lora_config.sck_io_num = (gpio_num_t)LORA_SCK;
|
||||||
lora_config.miso_io_num = LORA_MISO;
|
lora_config.miso_io_num = (gpio_num_t)LORA_MISO;
|
||||||
lora_config.mosi_io_num = LORA_MOSI;
|
lora_config.mosi_io_num = (gpio_num_t)LORA_MOSI;
|
||||||
lora_config.cs_io_num = LORA_CS;
|
lora_config.cs_io_num = (gpio_num_t)LORA_CS;
|
||||||
lora_config.rst_io_num = LORA_RST;
|
lora_config.rst_io_num = (gpio_num_t)LORA_RST;
|
||||||
lora_config.irq_io_num = LORA_IRQ;
|
lora_config.irq_io_num = (gpio_num_t)LORA_IRQ;
|
||||||
lora_config.frequency = LORA_FREQ;
|
lora_config.frequency = LORA_FREQ;
|
||||||
lora_config.tx_power = 17;
|
lora_config.tx_power = 17;
|
||||||
lora_config.spreading_factor = 12;
|
lora_config.spreading_factor = 12;
|
||||||
@ -37,10 +37,11 @@ void ugv_comms_init() {
|
|||||||
lora_config.sync_word = 0x34;
|
lora_config.sync_word = 0x34;
|
||||||
lora_config.crc = SX127X_CRC_ENABLED;
|
lora_config.crc = SX127X_CRC_ENABLED;
|
||||||
|
|
||||||
esp_err_t ret;
|
esp_err_t ret;
|
||||||
uas_ugv_Location loc = uas_ugv_Location_init_default;
|
|
||||||
|
uas::ugv::Location loc;
|
||||||
memcpy(&st->location, &loc, sizeof(loc));
|
memcpy(&st->location, &loc, sizeof(loc));
|
||||||
st->ugv_state = uas_ugv_UGV_State_IDLE;
|
st->ugv_state = uas::ugv::UGV_State::IDLE;
|
||||||
st->last_packet_tick = 0;
|
st->last_packet_tick = 0;
|
||||||
st->last_packet_rssi = INT32_MIN;
|
st->last_packet_rssi = INT32_MIN;
|
||||||
st->last_packet_snr = INT8_MIN;
|
st->last_packet_snr = INT8_MIN;
|
||||||
@ -73,13 +74,14 @@ static void ugv_comms_task(void *param) {
|
|||||||
esp_err_t ret;
|
esp_err_t ret;
|
||||||
sx127x_rx_packet_t rx_packet;
|
sx127x_rx_packet_t rx_packet;
|
||||||
|
|
||||||
uas_ugv_UGV_Message ugv_message = uas_ugv_UGV_Message_init_default;
|
uas::ugv::UGV_Message ugv_message;
|
||||||
ugv_message.which_ugv_message = uas_ugv_UGV_Message_status_tag;
|
uas::ugv::UGV_Status *status = ugv_message.mutable_status();
|
||||||
ugv_message.ugv_message.status.location.fix_quality = 0;
|
uas::ugv::Location * location = status->mutable_location();
|
||||||
ugv_message.ugv_message.status.location.latitude = 43.65;
|
location->set_fix_quality(0);
|
||||||
ugv_message.ugv_message.status.location.longitude = -116.20;
|
location->set_latitude(43.65);
|
||||||
ugv_message.ugv_message.status.location.altitude = 2730;
|
location->set_longitude(-116.20);
|
||||||
ugv_message.ugv_message.status.state = uas_ugv_UGV_State_IDLE;
|
location->set_altitude(2730);
|
||||||
|
status->set_state(uas::ugv::UGV_State::IDLE);
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
TickType_t delay_ticks = next_send - current_tick;
|
TickType_t delay_ticks = next_send - current_tick;
|
||||||
@ -97,9 +99,12 @@ static void ugv_comms_task(void *param) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
packet_num++;
|
packet_num++;
|
||||||
ret = sx127x_send_packet_pb(st->lora, uas_ugv_UGV_Message_fields,
|
auto str = ugv_message.SerializeAsString();
|
||||||
&ugv_message,
|
ret = sx127x_send_packet(st->lora, str.c_str(), str.size(),
|
||||||
0); // 0 means error if queue full
|
0); // 0 means error if queue full
|
||||||
|
// ret = sx127x_send_packet_pb(st->lora, uas_ugv_UGV_Message_fields,
|
||||||
|
// &ugv_message,
|
||||||
|
// 0); // 0 means error if queue full
|
||||||
if (ret != ESP_OK) {
|
if (ret != ESP_OK) {
|
||||||
ESP_LOGE(TAG, "error sending packet: %d", ret);
|
ESP_LOGE(TAG, "error sending packet: %d", ret);
|
||||||
} else {
|
} else {
|
||||||
@ -123,37 +128,34 @@ static void ugv_comms_handle_packet(ugv_comms_state_t * st,
|
|||||||
st->last_packet_snr = rx_packet->snr;
|
st->last_packet_snr = rx_packet->snr;
|
||||||
xSemaphoreGive(st->mutex);
|
xSemaphoreGive(st->mutex);
|
||||||
|
|
||||||
uas_ugv_GroundMessage ground_message = uas_ugv_GroundMessage_init_default;
|
uas::ugv::GroundMessage ground_message;
|
||||||
pb_istream_t istream;
|
bool pb_ret;
|
||||||
bool pb_ret;
|
|
||||||
|
|
||||||
istream =
|
pb_ret = ground_message.ParseFromArray(rx_packet->data, rx_packet->data_len);
|
||||||
pb_istream_from_buffer((pb_byte_t *)rx_packet->data, rx_packet->data_len);
|
|
||||||
pb_ret = pb_decode(&istream, uas_ugv_GroundMessage_fields, &ground_message);
|
|
||||||
if (!pb_ret) {
|
if (!pb_ret) {
|
||||||
ESP_LOGE(TAG, "rx invalid protobuf");
|
ESP_LOGE(TAG, "rx invalid protobuf");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (ground_message.which_ground_message) {
|
switch (ground_message.ground_message_case()) {
|
||||||
case uas_ugv_GroundMessage_command_tag:
|
case uas::ugv::GroundMessage::kCommand:
|
||||||
ugv_comms_handle_command(st, &ground_message.ground_message.command);
|
ugv_comms_handle_command(st, &ground_message.command());
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
ESP_LOGE(TAG, "invalid ground message: %d",
|
ESP_LOGE(TAG, "invalid ground message: %d",
|
||||||
ground_message.which_ground_message);
|
ground_message.ground_message_case());
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void ugv_comms_handle_command(ugv_comms_state_t * st,
|
static void ugv_comms_handle_command(ugv_comms_state_t * st,
|
||||||
uas_ugv_GroundCommand *command) {
|
const uas::ugv::GroundCommand *command) {
|
||||||
ESP_LOGI(TAG, "rx command id %d type %d", command->id, command->type);
|
ESP_LOGI(TAG, "rx command id %d type %d", command->id(), command->type());
|
||||||
// TODO: handle command
|
// TODO: handle command
|
||||||
|
|
||||||
uas_ugv_UGV_Message ugv_message = uas_ugv_UGV_Message_init_default;
|
uas::ugv::UGV_Message ugv_message;
|
||||||
ugv_message.which_ugv_message = uas_ugv_UGV_Message_command_ack_tag;
|
ugv_message.set_command_ack(command->id());
|
||||||
ugv_message.ugv_message.command_ack = command->id;
|
|
||||||
|
|
||||||
sx127x_send_packet_pb(st->lora, uas_ugv_UGV_Message_fields, &ugv_message, 0);
|
std::string str = ugv_message.SerializeAsString();
|
||||||
|
sx127x_send_packet(st->lora, str.c_str(), str.size(), 0);
|
||||||
}
|
}
|
@ -15,15 +15,15 @@ typedef struct ugv_comms_state_s {
|
|||||||
sx127x_hndl lora;
|
sx127x_hndl lora;
|
||||||
TaskHandle_t task_handle;
|
TaskHandle_t task_handle;
|
||||||
|
|
||||||
SemaphoreHandle_t mutex;
|
SemaphoreHandle_t mutex;
|
||||||
uas_ugv_Location location;
|
uas::ugv::Location location;
|
||||||
uas_ugv_UGV_State ugv_state;
|
uas::ugv::UGV_State ugv_state;
|
||||||
TickType_t last_packet_tick;
|
TickType_t last_packet_tick;
|
||||||
int32_t last_packet_rssi;
|
int32_t last_packet_rssi;
|
||||||
int8_t last_packet_snr;
|
int8_t last_packet_snr;
|
||||||
} ugv_comms_state_t;
|
} ugv_comms_state_t;
|
||||||
|
|
||||||
ugv_comms_state_t ugv_comms_state;
|
extern ugv_comms_state_t ugv_comms_state;
|
||||||
|
|
||||||
void ugv_comms_init();
|
void ugv_comms_init();
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user