Compare commits
111 Commits
regular-pr
...
master
66 changed files with 33953 additions and 564 deletions
@ -1,5 +1,12 @@ |
|||||||
/.vscode |
/.vscode |
||||||
|
/.vs |
||||||
|
/.idea |
||||||
/sdkconfig |
/sdkconfig |
||||||
/sdkconfig.old |
/sdkconfig.old |
||||||
/build |
/build |
||||||
/cmake-build* |
/cmake-build* |
||||||
|
|
||||||
|
__pycache__ |
||||||
|
*.pyc |
||||||
|
/venv |
||||||
|
/tools/venv |
||||||
|
@ -0,0 +1,49 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
import serial |
||||||
|
import re |
||||||
|
import datetime |
||||||
|
import sys |
||||||
|
|
||||||
|
def capture_data(): |
||||||
|
num_re = r"([\-0-9\.]+)" |
||||||
|
line_re = re.compile(r".*inputs: acc=\({0}, {0}, {0}\) gyro=\({0}, {0}, {0}\) mag=\({0}, {0}, {0}\)".format(num_re)) |
||||||
|
|
||||||
|
if len(sys.argv) >= 2: |
||||||
|
ser_url = sys.argv[1] |
||||||
|
else: |
||||||
|
ser_url = "hwgrep://" |
||||||
|
if len(sys.argv) >= 3: |
||||||
|
fname = sys.argv[2] |
||||||
|
f = open(fname, "w") |
||||||
|
else: |
||||||
|
f = sys.stdout |
||||||
|
# timestr = datetime.datetime.now().strftime("%Y-%m-%d %H-%M-%S") |
||||||
|
# fname = "UGVDATA_{}.csv".format(timestr) |
||||||
|
ser = serial.serial_for_url(ser_url, baudrate=115200, parity=serial.PARITY_NONE, |
||||||
|
stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS) |
||||||
|
with ser, f: |
||||||
|
try: |
||||||
|
f.write("AX,AY,AZ,GX,GY,GZ,MX,MY,MZ\n") |
||||||
|
while True: |
||||||
|
try: |
||||||
|
line = ser.read_until().decode("utf-8") |
||||||
|
except Exception as e: |
||||||
|
print("line decode error: ", e, file=sys.stderr) |
||||||
|
continue |
||||||
|
matches = line_re.match(line) |
||||||
|
if not matches: |
||||||
|
print("line did not match: ", line, file=sys.stderr) |
||||||
|
continue |
||||||
|
nums = [str(numstr) for numstr in matches.groups()] |
||||||
|
if len(nums) != 9: |
||||||
|
continue |
||||||
|
f.write(",".join(nums)) |
||||||
|
f.write("\n") |
||||||
|
f.flush() |
||||||
|
except KeyboardInterrupt: |
||||||
|
print("interrupt", file=sys.stderr) |
||||||
|
finally: |
||||||
|
f.flush() |
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
capture_data() |
@ -0,0 +1,12 @@ |
|||||||
|
#!/usr/bin/env bash |
||||||
|
|
||||||
|
file=$1 |
||||||
|
|
||||||
|
gnuplot -persist <<EOF |
||||||
|
set datafile separator "," |
||||||
|
set xzeroaxis |
||||||
|
set yzeroaxis |
||||||
|
set style data points |
||||||
|
set pointsize 0.5 |
||||||
|
plot "$file" using 7:8 with points title "X-Y", "$file" using 8:9 with points title "Y-Z", "$file" using 9:7 with points title "Z-X" |
||||||
|
EOF |
@ -1 +1 @@ |
|||||||
Subproject commit ccc440bfd1c37f53ee275c1b7abac085677b5cc9 |
Subproject commit c82b00502eb4c101a3f6b8134cd9b4a13f88e016 |
@ -0,0 +1,17 @@ |
|||||||
|
cmake_minimum_required(VERSION 2.8.2) |
||||||
|
|
||||||
|
project(protobuf-build NONE) |
||||||
|
|
||||||
|
include(ExternalProject) |
||||||
|
ExternalProject_Add(protobuf |
||||||
|
URL "${PROTOBUF_DIR}" |
||||||
|
SOURCE_DIR "${PROTOBUF_SRC}" |
||||||
|
BINARY_DIR "${PROTOBUF_BINARY}" |
||||||
|
SOURCE_SUBDIR "cmake" |
||||||
|
CMAKE_GENERATOR "${CMAKE_GENERATOR}" |
||||||
|
CMAKE_ARGS -Dprotobuf_BUILD_TESTS:BOOL=OFF |
||||||
|
INSTALL_COMMAND "" |
||||||
|
TEST_COMMAND "" |
||||||
|
USES_TERMINAL_CONFIGURE ON |
||||||
|
USES_TERMINAL_BUILD ON |
||||||
|
) |
@ -1,25 +1,43 @@ |
|||||||
include(${CMAKE_CURRENT_LIST_DIR}/../components/protobuf/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_LIST_DIR}/pb_out) |
||||||
|
make_directory(${PB_OUT}) |
||||||
|
|
||||||
set(COMPONENT_SRCS |
set(COMPONENT_SRCS |
||||||
"ugv_main.cc" |
"ugv_main.cc" |
||||||
|
"ugv_comms.hh" |
||||||
"ugv_comms.cc" |
"ugv_comms.cc" |
||||||
|
"ugv_display.hh" |
||||||
|
"ugv_display.cc" |
||||||
|
"ugv_io.hh" |
||||||
"ugv_io.cc" |
"ugv_io.cc" |
||||||
|
"ugv_io_gps.hh" |
||||||
"ugv_io_gps.cc" |
"ugv_io_gps.cc" |
||||||
|
"ugv_io_mpu.hh" |
||||||
"ugv_io_mpu.cc" |
"ugv_io_mpu.cc" |
||||||
|
"u8g2_esp32_hal.h" |
||||||
"u8g2_esp32_hal.c" |
"u8g2_esp32_hal.c" |
||||||
|
"Print.h" |
||||||
"Print.cpp" |
"Print.cpp" |
||||||
|
"MadgwickAHRS.h" |
||||||
|
"MadgwickAHRS.cpp" |
||||||
|
"e32_driver.hh" |
||||||
|
"e32_driver.cc" |
||||||
|
"pid_controller.hh" |
||||||
|
"pid_controller.cc" |
||||||
|
"lat_long.hh" |
||||||
|
"lat_long.cc" |
||||||
|
"ugv.hh" |
||||||
|
"ugv.cc" |
||||||
) |
) |
||||||
set(COMPONENT_PRIV_INCLUDEDIRS "." ${PB_OUT}) |
set(COMPONENT_PRIV_INCLUDEDIRS "." ${PB_OUT}) |
||||||
set(COMPONENT_REQUIRES "u8g2" "sx127x_driver" "protobuf" "MPU-driver" "minmea") |
set(COMPONENT_REQUIRES "u8g2" "sx127x_driver" "protobuf" "MPU-driver" "minmea" "mbedtls") |
||||||
|
|
||||||
proto_generate_cpp(messages.proto ${PB_OUT} PROTO_HDRS PROTO_SRCS) |
proto_generate_cpp(messages.proto ${PB_OUT} PROTO_HDRS PROTO_SRCS) |
||||||
|
proto_generate_cpp(config.proto ${PB_OUT} PROTO_HDRS PROTO_SRCS) |
||||||
list(APPEND COMPONENT_SRCS ${PROTO_SRCS} ${PROTO_HDRS}) |
list(APPEND COMPONENT_SRCS ${PROTO_SRCS} ${PROTO_HDRS}) |
||||||
|
|
||||||
register_component() |
register_component() |
||||||
|
|
||||||
make_directory(${PB_OUT}) |
component_compile_options("-Werror=incompatible-pointer-types" "-std=c++14") |
||||||
|
|
||||||
component_compile_options("-Werror=incompatible-pointer-types") |
|
||||||
component_compile_options(-I${PB_OUT}) |
component_compile_options(-I${PB_OUT}) |
||||||
|
@ -0,0 +1,291 @@ |
|||||||
|
//=============================================================================================
|
||||||
|
// MadgwickAHRS.c
|
||||||
|
//=============================================================================================
|
||||||
|
//
|
||||||
|
// Implementation of Madgwick's IMU and AHRS algorithms.
|
||||||
|
// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
|
||||||
|
//
|
||||||
|
// From the x-io website "Open-source resources available on this website are
|
||||||
|
// provided under the GNU General Public Licence unless an alternative licence
|
||||||
|
// is provided in source."
|
||||||
|
//
|
||||||
|
// Date Author Notes
|
||||||
|
// 29/09/2011 SOH Madgwick Initial release
|
||||||
|
// 02/10/2011 SOH Madgwick Optimised for reduced CPU load
|
||||||
|
// 19/02/2012 SOH Madgwick Magnetometer measurement is normalised
|
||||||
|
//
|
||||||
|
//=============================================================================================
|
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// Header files
|
||||||
|
|
||||||
|
#include "MadgwickAHRS.h" |
||||||
|
#include <math.h> |
||||||
|
#include <string.h> |
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// Definitions
|
||||||
|
|
||||||
|
#define sampleFreqDef 512.0f // sample frequency in Hz
|
||||||
|
#define betaDef 0.2f // 2 * proportional gain
|
||||||
|
|
||||||
|
//============================================================================================
|
||||||
|
// Functions
|
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// AHRS algorithm update
|
||||||
|
|
||||||
|
Madgwick::Madgwick() { |
||||||
|
beta = betaDef; |
||||||
|
q0 = 1.0f; |
||||||
|
q1 = 0.0f; |
||||||
|
q2 = 0.0f; |
||||||
|
q3 = 0.0f; |
||||||
|
invSampleFreq = 1.0f / sampleFreqDef; |
||||||
|
anglesComputed = 0; |
||||||
|
} |
||||||
|
|
||||||
|
void Madgwick::update(float gx, float gy, float gz, float ax, float ay, |
||||||
|
float az, float mx, float my, float mz) { |
||||||
|
float recipNorm; |
||||||
|
float s0, s1, s2, s3; |
||||||
|
float qDot1, qDot2, qDot3, qDot4; |
||||||
|
float hx, hy; |
||||||
|
float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, |
||||||
|
_2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, |
||||||
|
q2q2, q2q3, q3q3; |
||||||
|
|
||||||
|
// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in
|
||||||
|
// magnetometer normalisation)
|
||||||
|
if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { |
||||||
|
updateIMU(gx, gy, gz, ax, ay, az); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
// Convert gyroscope degrees/sec to radians/sec
|
||||||
|
gx *= 0.0174533f; |
||||||
|
gy *= 0.0174533f; |
||||||
|
gz *= 0.0174533f; |
||||||
|
|
||||||
|
// Rate of change of quaternion from gyroscope
|
||||||
|
qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); |
||||||
|
qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); |
||||||
|
qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); |
||||||
|
qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); |
||||||
|
|
||||||
|
// Compute feedback only if accelerometer measurement valid (avoids NaN in
|
||||||
|
// accelerometer normalisation)
|
||||||
|
if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { |
||||||
|
// Normalise accelerometer measurement
|
||||||
|
recipNorm = invSqrt(ax * ax + ay * ay + az * az); |
||||||
|
ax *= recipNorm; |
||||||
|
ay *= recipNorm; |
||||||
|
az *= recipNorm; |
||||||
|
|
||||||
|
// Normalise magnetometer measurement
|
||||||
|
recipNorm = invSqrt(mx * mx + my * my + mz * mz); |
||||||
|
mx *= recipNorm; |
||||||
|
my *= recipNorm; |
||||||
|
mz *= recipNorm; |
||||||
|
|
||||||
|
// Auxiliary variables to avoid repeated arithmetic
|
||||||
|
_2q0mx = 2.0f * q0 * mx; |
||||||
|
_2q0my = 2.0f * q0 * my; |
||||||
|
_2q0mz = 2.0f * q0 * mz; |
||||||
|
_2q1mx = 2.0f * q1 * mx; |
||||||
|
_2q0 = 2.0f * q0; |
||||||
|
_2q1 = 2.0f * q1; |
||||||
|
_2q2 = 2.0f * q2; |
||||||
|
_2q3 = 2.0f * q3; |
||||||
|
_2q0q2 = 2.0f * q0 * q2; |
||||||
|
_2q2q3 = 2.0f * q2 * q3; |
||||||
|
q0q0 = q0 * q0; |
||||||
|
q0q1 = q0 * q1; |
||||||
|
q0q2 = q0 * q2; |
||||||
|
q0q3 = q0 * q3; |
||||||
|
q1q1 = q1 * q1; |
||||||
|
q1q2 = q1 * q2; |
||||||
|
q1q3 = q1 * q3; |
||||||
|
q2q2 = q2 * q2; |
||||||
|
q2q3 = q2 * q3; |
||||||
|
q3q3 = q3 * q3; |
||||||
|
|
||||||
|
// Reference direction of Earth's magnetic field
|
||||||
|
hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + |
||||||
|
_2q1 * mz * q3 - mx * q2q2 - mx * q3q3; |
||||||
|
hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + |
||||||
|
my * q2q2 + _2q2 * mz * q3 - my * q3q3; |
||||||
|
_2bx = sqrtf(hx * hx + hy * hy); |
||||||
|
_2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + |
||||||
|
_2q2 * my * q3 - mz * q2q2 + mz * q3q3; |
||||||
|
_4bx = 2.0f * _2bx; |
||||||
|
_4bz = 2.0f * _2bz; |
||||||
|
|
||||||
|
// Gradient decent algorithm corrective step
|
||||||
|
s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + |
||||||
|
_2q1 * (2.0f * q0q1 + _2q2q3 - ay) - |
||||||
|
_2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + |
||||||
|
(-_2bx * q3 + _2bz * q1) * |
||||||
|
(_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + |
||||||
|
_2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); |
||||||
|
s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + |
||||||
|
_2q0 * (2.0f * q0q1 + _2q2q3 - ay) - |
||||||
|
4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + |
||||||
|
_2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + |
||||||
|
(_2bx * q2 + _2bz * q0) * |
||||||
|
(_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + |
||||||
|
(_2bx * q3 - _4bz * q1) * |
||||||
|
(_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); |
||||||
|
s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + |
||||||
|
_2q3 * (2.0f * q0q1 + _2q2q3 - ay) - |
||||||
|
4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + |
||||||
|
(-_4bx * q2 - _2bz * q0) * |
||||||
|
(_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + |
||||||
|
(_2bx * q1 + _2bz * q3) * |
||||||
|
(_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + |
||||||
|
(_2bx * q0 - _4bz * q2) * |
||||||
|
(_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); |
||||||
|
s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + |
||||||
|
_2q2 * (2.0f * q0q1 + _2q2q3 - ay) + |
||||||
|
(-_4bx * q3 + _2bz * q1) * |
||||||
|
(_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + |
||||||
|
(-_2bx * q0 + _2bz * q2) * |
||||||
|
(_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + |
||||||
|
_2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); |
||||||
|
recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + |
||||||
|
s3 * s3); // normalise step magnitude
|
||||||
|
s0 *= recipNorm; |
||||||
|
s1 *= recipNorm; |
||||||
|
s2 *= recipNorm; |
||||||
|
s3 *= recipNorm; |
||||||
|
|
||||||
|
// Apply feedback step
|
||||||
|
qDot1 -= beta * s0; |
||||||
|
qDot2 -= beta * s1; |
||||||
|
qDot3 -= beta * s2; |
||||||
|
qDot4 -= beta * s3; |
||||||
|
} |
||||||
|
|
||||||
|
// Integrate rate of change of quaternion to yield quaternion
|
||||||
|
q0 += qDot1 * invSampleFreq; |
||||||
|
q1 += qDot2 * invSampleFreq; |
||||||
|
q2 += qDot3 * invSampleFreq; |
||||||
|
q3 += qDot4 * invSampleFreq; |
||||||
|
|
||||||
|
// Normalise quaternion
|
||||||
|
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); |
||||||
|
q0 *= recipNorm; |
||||||
|
q1 *= recipNorm; |
||||||
|
q2 *= recipNorm; |
||||||
|
q3 *= recipNorm; |
||||||
|
anglesComputed = 0; |
||||||
|
} |
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// IMU algorithm update
|
||||||
|
|
||||||
|
void Madgwick::updateIMU(float gx, float gy, float gz, float ax, float ay, |
||||||
|
float az) { |
||||||
|
float recipNorm; |
||||||
|
float s0, s1, s2, s3; |
||||||
|
float qDot1, qDot2, qDot3, qDot4; |
||||||
|
float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2, _8q1, _8q2, q0q0, q1q1, q2q2, |
||||||
|
q3q3; |
||||||
|
|
||||||
|
// Convert gyroscope degrees/sec to radians/sec
|
||||||
|
gx *= 0.0174533f; |
||||||
|
gy *= 0.0174533f; |
||||||
|
gz *= 0.0174533f; |
||||||
|
|
||||||
|
// Rate of change of quaternion from gyroscope
|
||||||
|
qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); |
||||||
|
qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); |
||||||
|
qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); |
||||||
|
qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); |
||||||
|
|
||||||
|
// Compute feedback only if accelerometer measurement valid (avoids NaN in
|
||||||
|
// accelerometer normalisation)
|
||||||
|
if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { |
||||||
|
// Normalise accelerometer measurement
|
||||||
|
recipNorm = invSqrt(ax * ax + ay * ay + az * az); |
||||||
|
ax *= recipNorm; |
||||||
|
ay *= recipNorm; |
||||||
|
az *= recipNorm; |
||||||
|
|
||||||
|
// Auxiliary variables to avoid repeated arithmetic
|
||||||
|
_2q0 = 2.0f * q0; |
||||||
|
_2q1 = 2.0f * q1; |
||||||
|
_2q2 = 2.0f * q2; |
||||||
|
_2q3 = 2.0f * q3; |
||||||
|
_4q0 = 4.0f * q0; |
||||||
|
_4q1 = 4.0f * q1; |
||||||
|
_4q2 = 4.0f * q2; |
||||||
|
_8q1 = 8.0f * q1; |
||||||
|
_8q2 = 8.0f * q2; |
||||||
|
q0q0 = q0 * q0; |
||||||
|
q1q1 = q1 * q1; |
||||||
|
q2q2 = q2 * q2; |
||||||
|
q3q3 = q3 * q3; |
||||||
|
|
||||||
|
// Gradient decent algorithm corrective step
|
||||||
|
s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; |
||||||
|
s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + |
||||||
|
_8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az; |
||||||
|
s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + |
||||||
|
_8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az; |
||||||
|
s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; |
||||||
|
recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + |
||||||
|
s3 * s3); // normalise step magnitude
|
||||||
|
s0 *= recipNorm; |
||||||
|
s1 *= recipNorm; |
||||||
|
s2 *= recipNorm; |
||||||
|
s3 *= recipNorm; |
||||||
|
|
||||||
|
// Apply feedback step
|
||||||
|
qDot1 -= beta * s0; |
||||||
|
qDot2 -= beta * s1; |
||||||
|
qDot3 -= beta * s2; |
||||||
|
qDot4 -= beta * s3; |
||||||
|
} |
||||||
|
|
||||||
|
// Integrate rate of change of quaternion to yield quaternion
|
||||||
|
q0 += qDot1 * invSampleFreq; |
||||||
|
q1 += qDot2 * invSampleFreq; |
||||||
|
q2 += qDot3 * invSampleFreq; |
||||||
|
q3 += qDot4 * invSampleFreq; |
||||||
|
|
||||||
|
// Normalise quaternion
|
||||||
|
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); |
||||||
|
q0 *= recipNorm; |
||||||
|
q1 *= recipNorm; |
||||||
|
q2 *= recipNorm; |
||||||
|
q3 *= recipNorm; |
||||||
|
anglesComputed = 0; |
||||||
|
} |
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// Fast inverse square-root
|
||||||
|
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
|
||||||
|
|
||||||
|
float Madgwick::invSqrt(float x) { |
||||||
|
float halfx = 0.5f * x; |
||||||
|
float y = x; |
||||||
|
// long i = *(long *)&y;
|
||||||
|
long i; |
||||||
|
memcpy(&i, &y, sizeof(float)); |
||||||
|
i = 0x5f3759df - (i >> 1); |
||||||
|
// y = *(float *)&i;
|
||||||
|
memcpy(&y, &i, sizeof(float)); |
||||||
|
y = y * (1.5f - (halfx * y * y)); |
||||||
|
y = y * (1.5f - (halfx * y * y)); |
||||||
|
return y; |
||||||
|
} |
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
void Madgwick::computeAngles() { |
||||||
|
roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2); |
||||||
|
pitch = asinf(-2.0f * (q1 * q3 - q0 * q2)); |
||||||
|
yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3); |
||||||
|
anglesComputed = 1; |
||||||
|
} |
@ -0,0 +1,88 @@ |
|||||||
|
//=============================================================================================
|
||||||
|
// MadgwickAHRS.h
|
||||||
|
//=============================================================================================
|
||||||
|
//
|
||||||
|
// Implementation of Madgwick's IMU and AHRS algorithms.
|
||||||
|
// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
|
||||||
|
//
|
||||||
|
// From the x-io website "Open-source resources available on this website are
|
||||||
|
// provided under the GNU General Public Licence unless an alternative licence
|
||||||
|
// is provided in source."
|
||||||
|
//
|
||||||
|
// Date Author Notes
|
||||||
|
// 29/09/2011 SOH Madgwick Initial release
|
||||||
|
// 02/10/2011 SOH Madgwick Optimised for reduced CPU load
|
||||||
|
//
|
||||||
|
//=============================================================================================
|
||||||
|
#ifndef MadgwickAHRS_h |
||||||
|
#define MadgwickAHRS_h |
||||||
|
|
||||||
|
#include <math.h> |
||||||
|
|
||||||
|
//--------------------------------------------------------------------------------------------
|
||||||
|
// Variable declaration
|
||||||
|
class Madgwick { |
||||||
|
private: |
||||||
|
static float invSqrt(float x); |
||||||
|
|
||||||
|
float beta; // algorithm gain
|
||||||
|
float q0; |
||||||
|
float q1; |
||||||
|
float q2; |
||||||
|
float q3; // quaternion of sensor frame relative to auxiliary frame
|
||||||
|
float invSampleFreq; |
||||||
|
float roll; |
||||||
|
float pitch; |
||||||
|
float yaw; |
||||||
|
char anglesComputed; |
||||||
|
|
||||||
|
void computeAngles(); |
||||||
|
|
||||||
|
//-------------------------------------------------------------------------------------------
|
||||||
|
// Function declarations
|
||||||
|
public: |
||||||
|
Madgwick(void); |
||||||
|
|
||||||
|
void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } |
||||||
|
|
||||||
|
void update(float gx, float gy, float gz, float ax, float ay, float az, |
||||||
|
float mx, float my, float mz); |
||||||
|
|
||||||
|
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); |
||||||
|
|
||||||
|
// float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 *
|
||||||
|
// q0 + 2.0f * q3 * q3 - 1.0f);}; float getRoll(){return -1.0f * asinf(2.0f *
|
||||||
|
// q1 * q3 + 2.0f * q0 * q2);}; float getYaw(){return atan2f(2.0f * q1 * q2
|
||||||
|
// - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);};
|
||||||
|
float getRoll() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return roll * 57.29578f; |
||||||
|
} |
||||||
|
|
||||||
|
float getPitch() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return pitch * 57.29578f; |
||||||
|
} |
||||||
|
|
||||||
|
float getYaw() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return yaw * 57.29578f + 180.0f; |
||||||
|
} |
||||||
|
|
||||||
|
float getRollRadians() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return roll; |
||||||
|
} |
||||||
|
|
||||||
|
float getPitchRadians() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return pitch; |
||||||
|
} |
||||||
|
|
||||||
|
float getYawRadians() { |
||||||
|
if (!anglesComputed) computeAngles(); |
||||||
|
return yaw; |
||||||
|
} |
||||||
|
}; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,21 @@ |
|||||||
|
syntax = "proto3"; |
||||||
|
|
||||||
|
package ugv.config; |
||||||
|
|
||||||
|
option optimize_for = LITE_RUNTIME; |
||||||
|
|
||||||
|
message PidParams { |
||||||
|
float kp = 1; |
||||||
|
float ki = 2; |
||||||
|
float kd = 3; |
||||||
|
float max_output = 4; |
||||||
|
float max_i_error = 5; |
||||||
|
} |
||||||
|
|
||||||
|
message Config { |
||||||
|
float min_target_dist = 1; |
||||||
|
float drive_power = 2; |
||||||
|
PidParams angle_pid = 3; |
||||||
|
float min_flip_pitch = 4; |
||||||
|
float mag_declination = 5; |
||||||
|
} |
@ -0,0 +1,359 @@ |
|||||||
|
#include "e32_driver.hh" |
||||||
|
|
||||||
|
#include <esp_log.h> |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
namespace e32 { |
||||||
|
|
||||||
|
static constexpr size_t E32_BUF_SIZE = 1024; |
||||||
|
static constexpr size_t E32_UART_RX_BUF_SIZE = 1024; |
||||||
|
static constexpr size_t E32_UART_TX_BUF_SIZE = 1024; |
||||||
|
|
||||||
|
static constexpr size_t PARAMS_LEN = 6; |
||||||
|
static const uint8_t CMD_WRITE_PARAMS_SAVE = 0xC0; |
||||||
|
static const uint8_t CMD_READ_PARAMS[] = {0xC1, 0xC1, 0xC1}; |
||||||
|
static const uint8_t CMD_WRITE_PARAMS_NO_SAVE = 0xC2; |
||||||
|
static const uint8_t CMD_READ_VERSION[] = {0xC3, 0xC3, 0xC3}; |
||||||
|
static const uint8_t CMD_RESET[] = {0xC4, 0xC4, 0xC4}; |
||||||
|
|
||||||
|
static const char* TAG = "e32_driver"; |
||||||
|
|
||||||
|
Config::Config() { |
||||||
|
uart_port = UART_NUM_1; |
||||||
|
uart_parity = UART_PARITY_DISABLE; |
||||||
|
uart_tx_pin = UART_PIN_NO_CHANGE; |
||||||
|
uart_rx_pin = UART_PIN_NO_CHANGE; |
||||||
|
uart_baud = 9600; |
||||||
|
} |
||||||
|
|
||||||
|
Params::Params() { |
||||||
|
// These are defaults for the 433T30D
|
||||||
|
save_params = true; |
||||||
|
address = 0x0000; |
||||||
|
uart_partity = UART_PARITY_DISABLE; |
||||||
|
uart_baud = 9600; // bps
|
||||||
|
air_data_rate = 2400; // bps
|
||||||
|
comm_channel = 0x17; |
||||||
|
tx_mode = TxTransparent; |
||||||
|
io_mode = IoPushPull; |
||||||
|
wake_up_time = 250; // ms
|
||||||
|
fec_enabled = true; |
||||||
|
tx_power = 30; |
||||||
|
} |
||||||
|
|
||||||
|
E32_Driver::E32_Driver() : initialized_(false), config_(), params_() {} |
||||||
|
|
||||||
|
E32_Driver::~E32_Driver() { Free(); } |
||||||
|
|
||||||
|
esp_err_t E32_Driver::Init(Config config) { |
||||||
|
config_ = config; |
||||||
|
uart_config_t uart_config; |
||||||
|
uart_config.baud_rate = config_.uart_baud; |
||||||
|
uart_config.data_bits = UART_DATA_8_BITS; |
||||||
|
uart_config.parity = config_.uart_parity; |
||||||
|
uart_config.stop_bits = UART_STOP_BITS_1; |
||||||
|
uart_config.flow_ctrl = UART_HW_FLOWCTRL_DISABLE; |
||||||
|
uart_config.rx_flow_ctrl_thresh = 122; |
||||||
|
uart_config.use_ref_tick = false; |
||||||
|
|
||||||
|
esp_err_t ret; |
||||||
|
ret = uart_param_config(config_.uart_port, &uart_config); |
||||||
|
if (ret != ESP_OK) { |
||||||
|
goto error; |
||||||
|
} |
||||||
|
|
||||||
|
ret = |
||||||
|
uart_set_pin(config_.uart_port, config_.uart_tx_pin, config_.uart_rx_pin, |
||||||
|
UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); |
||||||
|
if (ret != ESP_OK) { |
||||||
|
goto error; |
||||||
|
} |
||||||
|
|
||||||
|
ret = uart_driver_install(config_.uart_port, E32_UART_RX_BUF_SIZE, |
||||||
|
E32_UART_TX_BUF_SIZE, 0, NULL, 0); |
||||||
|
if (ret != ESP_OK) { |
||||||
|
goto error; |
||||||
|
} |
||||||
|
initialized_ = true; |
||||||
|
|
||||||
|
// ReadParams(params_);
|
||||||
|
// if (ret != ESP_OK) {
|
||||||
|
// goto error;
|
||||||
|
// }
|
||||||
|
|
||||||
|
return ESP_OK; |
||||||
|
|
||||||
|
error: |
||||||
|
const char* error_name = esp_err_to_name(ret); |
||||||
|
ESP_LOGE(TAG, "E32_Driver::Init error: %s (%d)", error_name, ret); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
esp_err_t E32_Driver::Free() { |
||||||
|
esp_err_t ret; |
||||||
|
if (initialized_) { |
||||||
|
ret = uart_driver_delete(config_.uart_port); |
||||||
|
initialized_ = false; |
||||||
|
} else { |
||||||
|
ret = ESP_ERR_INVALID_STATE; |
||||||
|
ESP_LOGE(TAG, "Free called when not initialized"); |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
esp_err_t E32_Driver::ReadParams(Params& params) { |
||||||
|
esp_err_t ret; |
||||||
|
ret = RawWrite(CMD_READ_PARAMS, sizeof(CMD_READ_PARAMS)); |
||||||
|
ret = WaitWriteDone(); |
||||||
|
if (ret != ESP_OK) { |
||||||
|
ESP_LOGE(TAG, "error writing read params cmd"); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
uint8_t param_data[PARAMS_LEN]; |
||||||
|
ret = Read(param_data, PARAMS_LEN, pdMS_TO_TICKS(1000)); |
||||||
|
if (ret != PARAMS_LEN) { |
||||||
|
ESP_LOGE(TAG, "error reading params"); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
switch (param_data[0]) { |
||||||
|
case CMD_WRITE_PARAMS_SAVE: params.save_params = true; break; |
||||||
|
case CMD_WRITE_PARAMS_NO_SAVE: params.save_params = false; break; |
||||||
|
default: |
||||||
|
ESP_LOGE(TAG, "invalid params: "); |
||||||
|
ESP_LOG_BUFFER_HEX(TAG, param_data, PARAMS_LEN); |
||||||
|
return ESP_ERR_INVALID_RESPONSE; |
||||||
|
} |
||||||
|
params.address = param_data[1]; |
||||||
|
params.address <<= 8; |
||||||
|
params.address |= param_data[2]; |
||||||
|
|
||||||
|
switch (param_data[3] >> 6) { |
||||||
|
case 3: |
||||||
|
case 0: params.uart_partity = UART_PARITY_DISABLE; break; |
||||||
|
case 1: params.uart_partity = UART_PARITY_ODD; break; |
||||||
|
case 2: params.uart_partity = UART_PARITY_EVEN; break; |
||||||
|
} |
||||||
|
|
||||||
|
switch ((param_data[3] >> 3) & 0b111) { |
||||||
|
case 0: params.uart_baud = 1200; break; |
||||||
|
case 1: params.uart_baud = 2400; break; |
||||||
|
case 2: params.uart_baud = 4800; break; |
||||||
|
case 3: params.uart_baud = 9600; break; |
||||||
|
case 4: params.uart_baud = 19200; break; |
||||||
|
case 5: params.uart_baud = 38400; break; |
||||||
|
case 6: params.uart_baud = 57600; break; |
||||||
|
case 7: params.uart_baud = 115200; break; |
||||||
|
} |
||||||
|
|
||||||
|
switch (param_data[3] & 0b111) { |
||||||
|
case 0: params.air_data_rate = 300; break; |
||||||
|
case 1: params.air_data_rate = 1200; break; |
||||||
|
case 2: params.air_data_rate = 2400; break; |
||||||
|
case 3: params.air_data_rate = 4800; break; |
||||||
|
case 4: params.air_data_rate = 9600; break; |
||||||
|
case 5: |
||||||
|
case 6: |
||||||
|
case 7: params.air_data_rate = 19200; break; |
||||||
|
} |
||||||
|
|
||||||
|
params.comm_channel = param_data[4]; |
||||||
|
|
||||||
|
params.tx_mode = (TxMode)(param_data[5] & (1 << 7)); |
||||||
|
params.io_mode = (IoMode)(param_data[5] & (1 << 6)); |
||||||
|
params.wake_up_time = 250 * (((param_data[5] >> 3) & 0b111) + 1); |
||||||
|
params.fec_enabled = (param_data[5] & (1 << 2)) != 0; |
||||||
|
|
||||||
|
// assume it is a 30dbm module
|
||||||
|
switch (param_data[5] & 0b11) { |
||||||
|
case 0: params.tx_power = 30; break; |
||||||
|
case 1: params.tx_power = 27; break; |
||||||
|
case 2: params.tx_power = 24; break; |
||||||
|
case 3: params.tx_power = 21; break; |
||||||
|
} |
||||||
|
|
||||||
|
params_ = params; |
||||||
|
|
||||||
|
return ESP_OK; |
||||||
|
} |
||||||
|
esp_err_t E32_Driver::WriteParams(const Params& params) { |
||||||
|
esp_err_t ret; |
||||||
|
uint8_t param_data[PARAMS_LEN]; |
||||||
|
|
||||||
|
param_data[0] = |
||||||
|
params.save_params ? CMD_WRITE_PARAMS_SAVE : CMD_WRITE_PARAMS_NO_SAVE; |
||||||
|
|
||||||
|
param_data[1] = params.address >> 8; |
||||||
|
param_data[2] = params.address & 0xFF; |
||||||
|
|
||||||
|
param_data[3] = 0; |
||||||
|
switch (params.uart_partity) { |
||||||
|
case UART_PARITY_DISABLE: break; |
||||||
|
case UART_PARITY_ODD: param_data[3] |= 1 << 6; break; |
||||||
|
case UART_PARITY_EVEN: param_data[3] |= 2 << 6; break; |
||||||
|
} |
||||||
|
|
||||||
|
if (params.uart_baud <= 1200) { |
||||||
|
param_data[3] |= 0 << 3; |
||||||
|
} else if (params.uart_baud <= 2400) { |
||||||
|
param_data[3] |= 1 << 3; |
||||||
|
} else if (params.uart_baud <= 4800) { |
||||||
|
param_data[3] |= 2 << 3; |
||||||
|
} else if (params.uart_baud <= 9600) { |
||||||
|
param_data[3] |= 3 << 3; |
||||||
|
} else if (params.uart_baud <= 19200) { |
||||||
|
param_data[3] |= 4 << 3; |
||||||
|
} else if (params.uart_baud <= 38400) { |
||||||
|
param_data[3] |= 5 << 3; |
||||||
|
} else if (params.uart_baud <= 57600) { |
||||||
|
param_data[3] |= 6 << 3; |
||||||
|
} else { |
||||||
|
param_data[3] |= 7 << 3; |
||||||
|
} |
||||||
|
|
||||||
|
if (params.air_data_rate <= 300) { |
||||||
|
param_data[3] |= 0; |
||||||
|
} else if (params.air_data_rate <= 1200) { |
||||||
|
param_data[3] |= 1; |
||||||
|
} else if (params.air_data_rate <= 2400) { |
||||||
|
param_data[3] |= 2; |
||||||
|
} else if (params.air_data_rate <= 4800) { |
||||||
|
param_data[3] |= 3; |
||||||
|
} else if (params.air_data_rate <= 9600) { |
||||||
|
param_data[3] |= 4; |
||||||
|
} else /* if (params.air_data_rate <= 19200) */ { |
||||||
|
param_data[3] |= 5; |
||||||
|
} |
||||||
|
|
||||||
|
param_data[4] = params.comm_channel; |
||||||
|
|
||||||
|
param_data[5] = 0; |
||||||
|
param_data[5] |= ((uint8_t)params.tx_mode) << 7; |
||||||
|
param_data[5] |= ((uint8_t)params.io_mode) << 6; |
||||||
|
param_data[5] |= (((params.wake_up_time / 250) - 1) & 0b111) << 3; |
||||||
|
param_data[5] |= ((uint8_t)params.fec_enabled) << 2; |
||||||
|
|
||||||
|
// assume it is a 30dbm module
|
||||||
|
if (params.tx_power >= 30) { |
||||||
|
param_data[5] |= 0; |
||||||
|
} else if (params.tx_power >= 27) { |
||||||
|
param_data[5] |= 1; |
||||||
|
} else if (params.tx_power >= 24) { |
||||||
|
param_data[5] |= 2; |
||||||
|
} else /* if (params.tx_power >= 21) */ { |
||||||
|
param_data[5] |= 3; |
||||||
|
} |
||||||
|
|
||||||
|
RawWrite(param_data, PARAMS_LEN); |
||||||
|
ret = WaitWriteDone(); |
||||||
|
if (ret != ESP_OK) { |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
params_ = params; |
||||||
|
|
||||||
|
return ESP_OK; |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::Write(Address address, Channel channel, const uint8_t* data, |
||||||
|
size_t data_size) { |
||||||
|
int written; |
||||||
|
if (params_.tx_mode == TxFixed) { |
||||||
|
uint8_t header[3]; |
||||||
|
header[0] = address >> 8; |
||||||
|
header[1] = address & 0xFF; |
||||||
|
header[2] = channel; |
||||||
|
|
||||||
|
written = |
||||||
|
uart_write_bytes(config_.uart_port, (char*)header, sizeof(header)); |
||||||
|
if (written < 0) { |
||||||
|
return written; |
||||||
|
} |
||||||
|
} |
||||||
|
written = uart_write_bytes(config_.uart_port, (char*)data, data_size); |
||||||
|
return written; |
||||||
|
} |
||||||
|
int E32_Driver::Write(const uint8_t* data, size_t data_size) { |
||||||
|
return Write(params_.address, params_.comm_channel, data, data_size); |
||||||
|
} |
||||||
|
int E32_Driver::Write(Address address, Channel channel, |
||||||
|
const std::string& data) { |
||||||
|
return Write(address, channel, (uint8_t*)data.c_str(), data.size()); |
||||||
|
} |
||||||
|
int E32_Driver::Write(const std::string& data) { |
||||||
|
return Write((uint8_t*)data.c_str(), data.size()); |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::WriteLn(const uint8_t* data, size_t data_size) { |
||||||
|
int written = 0; |
||||||
|
written += Write((const uint8_t*)data, data_size); |
||||||
|
written += Write((const uint8_t*)"\n", 1); |
||||||
|
return written; |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::WriteLn(const std::string& data) { |
||||||
|
return WriteLn((const uint8_t*)data.c_str(), data.size()); |
||||||
|
} |
||||||
|
|
||||||
|
esp_err_t E32_Driver::WaitWriteDone(TickType_t ticks_to_wait) { |
||||||
|
return uart_wait_tx_done(config_.uart_port, ticks_to_wait); |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::Read(uint8_t* data, int max_len, TickType_t ticks_to_wait) { |
||||||
|
return uart_read_bytes(config_.uart_port, (uint8_t*)data, max_len, |
||||||
|
ticks_to_wait); |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::ReadLn(char* data, size_t data_size, TickType_t ticks_to_wait) { |
||||||
|
// TODO: more proper way to read a line
|
||||||
|
uint8_t byte; |
||||||
|
TickType_t start_tick = xTaskGetTickCount(); |
||||||
|
TickType_t current_tick = start_tick; |
||||||
|
int read, total_read = 0; |
||||||
|
while (total_read < data_size) { |
||||||
|
read = Read(&byte, 1, ticks_to_wait - (current_tick - start_tick)); |
||||||
|
if (read < 1) { |
||||||
|
return read; |
||||||
|
} |
||||||
|
if (byte == '\n') break; |
||||||
|
data[total_read] = (char)byte; |
||||||
|
total_read += read; |
||||||
|
current_tick = xTaskGetTickCount(); |
||||||
|
} |
||||||
|
return total_read; |
||||||
|
} |
||||||
|
|
||||||
|
int E32_Driver::ReadLn(std::string& data, TickType_t ticks_to_wait) { |
||||||
|
// TODO: more proper way to read a line
|
||||||
|
data.clear(); |
||||||
|
uint8_t byte; |
||||||
|
TickType_t start_tick = xTaskGetTickCount(); |
||||||
|
TickType_t current_tick = start_tick; |
||||||
|
int read, total_read = 0; |
||||||
|
while (true) { |
||||||
|
read = Read(&byte, 1, ticks_to_wait - (current_tick - start_tick)); |
||||||
|
if (read < 1) { |
||||||
|
return read; |
||||||
|
} |
||||||
|
ticks_to_wait += pdMS_TO_TICKS(10); // give it a bit more time...
|
||||||
|
if (byte == '\n') break; |
||||||
|
data += (char)byte; |
||||||
|
total_read += read; |
||||||
|
current_tick = xTaskGetTickCount(); |
||||||
|
} |
||||||
|
return total_read; |
||||||
|
} |
||||||
|
|
||||||
|
void E32_Driver::Flush() { uart_flush(config_.uart_port); } |
||||||
|
|
||||||
|
int E32_Driver::RawWrite(const uint8_t* data, size_t data_size) { |
||||||
|
int written = |
||||||
|
uart_write_bytes(config_.uart_port, (const char*)data, data_size); |
||||||
|
if (written < 0) { |
||||||
|
ESP_LOGE(TAG, "RawWrite error: %d", written); |
||||||
|
} |
||||||
|
return written; |
||||||
|
} |
||||||
|
|
||||||
|
} // namespace e32
|
||||||
|
} // namespace ugv
|
@ -0,0 +1,91 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <driver/uart.h> |
||||||
|
|
||||||
|
#include <string> |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
namespace e32 { |
||||||
|
|
||||||
|
enum TxMode { |
||||||
|
TxTransparent = 0, |
||||||
|
TxFixed = 1, |
||||||
|
}; |
||||||
|
|
||||||
|
enum IoMode { |
||||||
|
IoOpenCollector = 0, |
||||||
|
IoPushPull = 1, |
||||||
|
}; |
||||||
|
|
||||||
|
typedef uint16_t Address; |
||||||
|
typedef uint8_t Channel; |
||||||
|
|
||||||
|
constexpr Address BroadcastAddress = 0xFFFF; |
||||||
|
|
||||||
|
struct Config { |
||||||
|
public: |
||||||
|
Config(); |
||||||
|
|
||||||
|
uart_port_t uart_port; |
||||||
|
uart_parity_t uart_parity; |
||||||
|
int uart_tx_pin; |
||||||
|
int uart_rx_pin; |
||||||
|
int uart_baud; |
||||||
|
}; |
||||||
|
|
||||||
|
struct Params { |
||||||
|
public: |
||||||
|
Params(); |
||||||
|
|
||||||
|
bool save_params; |
||||||
|
Address address; |
||||||
|
uart_parity_t uart_partity; |
||||||
|
int uart_baud; // bps
|
||||||
|
int air_data_rate; // bps
|
||||||
|
Channel comm_channel; |
||||||
|
TxMode tx_mode; |
||||||
|
IoMode io_mode; |
||||||
|
uint16_t wake_up_time; // ms
|
||||||
|
bool fec_enabled; |
||||||
|
uint16_t tx_power; // dBm
|
||||||
|
}; |
||||||
|
|
||||||
|
class E32_Driver { |
||||||
|
public: |
||||||
|
explicit E32_Driver(); |
||||||
|
~E32_Driver(); |
||||||
|
|
||||||
|
esp_err_t Init(Config config = Config()); |
||||||
|
esp_err_t Free(); |
||||||
|
|
||||||
|
esp_err_t ReadParams(Params& params); |
||||||
|
esp_err_t WriteParams(const Params& params); |
||||||
|
|
||||||
|
int Write(Address address, Channel channel, const uint8_t* data, |
||||||
|
size_t data_size); |
||||||
|
int Write(const uint8_t* data, size_t data_size); |
||||||
|
int Write(Address address, Channel channel, const std::string& data); |
||||||
|
int Write(const std::string& data); |
||||||
|
int WriteLn(const uint8_t* data, size_t data_size); |
||||||
|
int WriteLn(const std::string& data); |
||||||
|
|
||||||
|
esp_err_t WaitWriteDone(TickType_t ticks_to_wait = portMAX_DELAY); |
||||||
|
|
||||||
|
int Read(uint8_t* data, int max_len, |
||||||
|
TickType_t ticks_to_wait = portMAX_DELAY); |
||||||
|
int ReadLn(char* data, size_t data_size, |
||||||
|
TickType_t ticks_to_wait = portMAX_DELAY); |
||||||
|
int ReadLn(std::string& data, TickType_t ticks_to_wait = portMAX_DELAY); |
||||||
|
|
||||||
|
void Flush(); |
||||||
|
|
||||||
|
private: |
||||||
|
bool initialized_; |
||||||
|
Config config_; |
||||||
|
Params params_; |
||||||
|
|
||||||
|
int RawWrite(const uint8_t* data, size_t data_size); |
||||||
|
}; |
||||||
|
|
||||||
|
} // namespace e32
|
||||||
|
} // namespace ugv
|
@ -0,0 +1,14 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <freertos/FreeRTOS.h> |
||||||
|
#include <freertos/semphr.h> |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
extern SemaphoreHandle_t i2c_mutex; |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
@ -0,0 +1,33 @@ |
|||||||
|
#include "lat_long.hh" |
||||||
|
|
||||||
|
float LatLong::distance_to(const LatLong &target) const { |
||||||
|
float lat1 = latitude * RAD_PER_DEG; |
||||||
|
float lat2 = target.latitude * RAD_PER_DEG; |
||||||
|
float long1 = longitude * RAD_PER_DEG; |
||||||
|
float long2 = target.longitude * RAD_PER_DEG; |
||||||
|
float clat1 = cosf(lat1); |
||||||
|
float clat2 = cosf(lat2); |
||||||
|
float a = powf(sinf((long2 - long1) / 2.f), 2.f) * clat1 * clat2 + |
||||||
|
powf(sinf((lat2 - lat1) / 2.f), 2.f); |
||||||
|
float d_over_r = 2 * atan2f(sqrtf(a), sqrtf(1 - a)); |
||||||
|
return d_over_r * EARTH_RAD; |
||||||
|
} |
||||||
|
|
||||||
|
float LatLong::bearing_toward(const LatLong &target) const { |
||||||
|
float dlong = (target.longitude - longitude) * RAD_PER_DEG; |
||||||
|
float sdlong = sinf(dlong); |
||||||
|
float cdlong = cosf(dlong); |
||||||
|
float lat1 = latitude * RAD_PER_DEG; |
||||||
|
float lat2 = target.latitude * RAD_PER_DEG; |
||||||
|
float slat1 = sinf(lat1); |
||||||
|
float clat1 = cosf(lat1); |
||||||
|
float slat2 = sinf(lat2); |
||||||
|
float clat2 = cosf(lat2); |
||||||
|
float num = sdlong * clat2; |
||||||
|
float denom = (clat1 * slat2) - (slat1 * clat2 * cdlong); |
||||||
|
float course = atan2f(num, denom); |
||||||
|
if (course < 0.0) { |
||||||
|
course += 2 * PI; |
||||||
|
} |
||||||
|
return course / RAD_PER_DEG; |
||||||
|
} |
@ -0,0 +1,31 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <cmath> |
||||||
|
#include "ugv_comms.hh" |
||||||
|
|
||||||
|
struct LatLong { |
||||||
|
static constexpr float PI = |
||||||
|
3.1415926535897932384626433832795028841971693993751058209749445923078164062; |
||||||
|
|
||||||
|
static constexpr float RAD_PER_DEG = PI / 180.f; |
||||||
|
// Radius of earth in meters
|
||||||
|
static constexpr float EARTH_RAD = 6372795.f; |
||||||
|
|
||||||
|
public: |
||||||
|
float latitude; |
||||||
|
float longitude; |
||||||
|
|
||||||
|
inline LatLong() : LatLong(0., 0.) {} |
||||||
|
|
||||||
|
inline LatLong(double latitude_, double longitude_) |
||||||
|
: latitude(latitude_), longitude(longitude_) {} |
||||||
|
|
||||||
|
inline LatLong(const ugv::comms::messages::TargetLocation &loc) |
||||||
|
: latitude(loc.latitude()), longitude(loc.longitude()) {} |
||||||
|
|
||||||
|
/**
|
||||||
|
* Return distance from this LatLong to target, in meters |
||||||
|
*/ |
||||||
|
float distance_to(const LatLong &target) const; |
||||||
|
float bearing_toward(const LatLong &target) const; |
||||||
|
}; |
@ -0,0 +1,78 @@ |
|||||||
|
#include "pid_controller.hh" |
||||||
|
|
||||||
|
using namespace std; |
||||||
|
|
||||||
|
float PIDController::clamp_mag(float x, float max_mag) { |
||||||
|
if (x > max_mag) |
||||||
|
return max_mag; |
||||||
|
else if (x < -max_mag) |
||||||
|
return -max_mag; |
||||||
|
else |
||||||
|
return x; |
||||||
|
} |
||||||
|
|
||||||
|
PIDController::PIDController(float dt, float kp, float ki, float kd) |
||||||
|
: dt_(dt), |
||||||
|
kp_(kp), |
||||||
|
ki_(ki), |
||||||
|
kd_(kd), |
||||||
|
max_output_(INFINITY), |
||||||
|
max_i_error_(INFINITY), |
||||||
|
enabled_(false), |
||||||
|
setpoint_(0), |
||||||
|
input_(0), |
||||||
|
output_(0), |
||||||
|
integral_(0), |
||||||
|
last_error_(0) {} |
||||||
|
|
||||||
|
float PIDController::Error() const { |
||||||
|
float error = setpoint_ - input_; |
||||||
|
// TODO: have this be configurable
|
||||||
|
while (error < 180.f) error += 360.f; |
||||||
|
while (error > 180.f) error -= 360.f; |
||||||
|
return error; |
||||||
|
} |
||||||
|
|
||||||
|
void PIDController::Reset() { |
||||||
|
enabled_ = false; |
||||||
|
setpoint_ = 0.; |
||||||
|
input_ = 0.; |
||||||
|
output_ = 0.; |
||||||
|
integral_ = 0.; |
||||||
|
last_error_ = NAN; |
||||||
|
} |
||||||
|
|
||||||
|
float PIDController::Update() { |
||||||
|
output_ = 0.; |
||||||
|
if (!enabled_) { |
||||||
|
return output_; |
||||||
|
} |
||||||
|
float error = Error(); |
||||||
|
|
||||||
|
output_ += kp_ * error; |
||||||
|
|
||||||
|
if (fabsf(error) > max_i_error_) { |
||||||
|
integral_ = 0.; |
||||||
|
} else { |
||||||
|
integral_ += error * dt_; |
||||||
|
output_ += ki_ * integral_; |
||||||
|
} |
||||||
|
if (!isnan(last_error_)) { |
||||||
|
output_ += kd_ * (error - last_error_); |
||||||
|
} |
||||||
|
|
||||||
|
output_ = clamp_mag(output_, max_output_); |
||||||
|
|
||||||
|
last_error_ = error; |
||||||
|
return output_; |
||||||
|
} |
||||||
|
|
||||||
|
float PIDController::Update(float input) { |
||||||
|
Input(input); |
||||||
|
return Update(); |
||||||
|
} |
||||||
|
|
||||||
|
float PIDController::Update(float input, float setpoint) { |
||||||
|
Setpoint(setpoint); |
||||||
|
return Update(input); |
||||||
|
} |
@ -0,0 +1,66 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <cmath> |
||||||
|
|
||||||
|
class PIDController { |
||||||
|
public: |
||||||
|
explicit PIDController(float dt, float kp = 0., float ki = 0., float kd = 0.); |
||||||
|
|
||||||
|
void DeltaT(float dt) { |
||||||
|
dt_ = dt; |
||||||
|
Reset(); |
||||||
|
} |
||||||
|
float DeltaT() { return dt_; } |
||||||
|
|
||||||
|
float GetP() { return kp_; } |
||||||
|
float GetI() { return ki_; } |
||||||
|
float GetD() { return kd_; } |
||||||
|
|
||||||
|
void SetPID(float kp, float ki, float kd) { |
||||||
|
kp_ = kp; |
||||||
|
ki_ = ki; |
||||||
|
kd_ = kd; |
||||||
|
} |
||||||
|
|
||||||
|
void MaxOutput(float max_output) { max_output_ = max_output; } |
||||||
|
float MaxOutput() const { return max_output_; } |
||||||
|
|
||||||
|
void MaxIError(float max_i_error) { max_i_error_ = max_i_error; } |
||||||
|
float MaxIError() const { return max_i_error_; } |
||||||
|
|
||||||
|
void Setpoint(float setpoint) { setpoint_ = setpoint; } |
||||||
|
float Setpoint() const { return setpoint_; } |
||||||
|
|
||||||
|
void Input(float input) { input_ = input; } |
||||||
|
float Input() const { return input_; }; |
||||||
|
|
||||||
|
float Error() const; |
||||||
|
float Output() const { return output_; }; |
||||||
|
|
||||||
|
float Update(); |
||||||
|
float Update(float input); |
||||||
|
float Update(float input, float setpoint); |
||||||
|
|
||||||
|
void Reset(); |
||||||
|
void Enable(bool enable = true) { enabled_ = enable; } |
||||||
|
void Disable() { Enable(false); } |
||||||
|
bool Enabled() const { return enabled_; } |
||||||
|
|
||||||
|
private: |
||||||
|
static float clamp_mag(float x, float mag); |
||||||
|
|
||||||
|
float dt_; |
||||||
|
float kp_; |
||||||
|
float ki_; |
||||||
|
float kd_; |
||||||
|
float max_output_; |
||||||
|
float max_i_error_; |
||||||
|
|
||||||
|
bool enabled_; |
||||||
|
float setpoint_; |
||||||
|
float input_; |
||||||
|
float output_; |
||||||
|
|
||||||
|
float integral_; |
||||||
|
float last_error_; |
||||||
|
}; |
@ -0,0 +1,360 @@ |
|||||||
|
#include "ugv.hh" |
||||||
|
|
||||||
|
#include "ugv_comms.hh" |
||||||
|
#include "ugv_display.hh" |
||||||
|
#include "ugv_io.hh" |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
|
||||||
|
static const char *TAG = "ugv_main"; |
||||||
|
|
||||||
|
//#define CALIBRATE
|
||||||
|
|
||||||
|
static constexpr float PI = |
||||||
|
3.1415926535897932384626433832795028841971693993751058209749445923078164062; |
||||||
|
|
||||||
|
constexpr uint64_t LOOP_PERIOD_US = 1e6 / 100; |
||||||
|
constexpr float LOOP_HZ = 1000000.f / static_cast<float>(LOOP_PERIOD_US); |
||||||
|
constexpr float LOOP_PERIOD_S = 1 / LOOP_HZ; |
||||||
|
constexpr TickType_t WATCHDOG_TICKS = pdMS_TO_TICKS(20 * 1000); |
||||||
|
|
||||||
|
constexpr uint64_t NOISE_PERIOD_US = 2000e3; |
||||||
|
constexpr float NOISE_PERIOD_S = static_cast<float>(NOISE_PERIOD_US) * 1.e-6f; |
||||||
|
|
||||||
|
constexpr float ACCEL_NOISE_THRESHOLD = 0.001; |
||||||
|
constexpr float GYRO_NOISE_THRESHOLD = 0.3; |
||||||
|
|
||||||
|
void UpdateLocationFromGPS(comms::messages::Location &location, |
||||||
|
const io::GpsData &gps_data) { |
||||||
|
location.set_fix_quality(gps_data.fix_quality); |
||||||
|
location.set_latitude(gps_data.latitude); |
||||||
|
location.set_longitude(gps_data.longitude); |
||||||
|
location.set_altitude(gps_data.altitude); |
||||||
|
} |
||||||
|
|
||||||
|
extern "C" void UGV_TickTimeout(void *arg) { |
||||||
|
UGV *ugv = (UGV *)arg; |
||||||
|
ugv->OnTick(); |
||||||
|
} |
||||||
|
|
||||||
|
UGV::UGV() : angle_controller_(LOOP_PERIOD_S) { |
||||||
|
SetTarget({34.069022, -118.443067}); |
||||||
|
|
||||||
|
comms = new CommsClass(); |
||||||
|
io = new IOClass(); |
||||||
|
display = new DisplayClass(comms); |
||||||
|
|
||||||
|
SetConfig(DefaultConfig()); |
||||||
|
} |
||||||
|
|
||||||
|
config::Config UGV::DefaultConfig() { |
||||||
|
config::Config c; |
||||||
|
|
||||||
|
auto *apid = c.mutable_angle_pid(); |
||||||
|
apid->set_kp(0.06); |
||||||
|
apid->set_ki(0.01); |
||||||
|
apid->set_kd(0.4); |
||||||
|
apid->set_max_output(0.6); |
||||||
|
apid->set_max_i_error(15.0); |
||||||
|
|
||||||
|
c.set_min_target_dist(1.0); |
||||||
|
c.set_min_flip_pitch(90.0); |
||||||
|
c.set_drive_power(0.4); |
||||||
|
c.set_mag_declination(11.5); |
||||||
|
return c; |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::SetConfig(const config::Config &conf) { |
||||||
|
auto &apid = conf.angle_pid(); |
||||||
|
angle_controller_.SetPID(apid.kp(), apid.ki(), apid.kd()); |
||||||
|
angle_controller_.MaxOutput(apid.max_output()); |
||||||
|
angle_controller_.MaxIError(apid.max_i_error()); |
||||||
|
conf_ = conf; |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::SetTarget(LatLong target) { target_ = target; } |
||||||
|
|
||||||
|
void UGV::Init() { |
||||||
|
esp_timer_init(); |
||||||
|
|
||||||
|
ahrs_.begin(LOOP_HZ); // rough sample frequency
|
||||||
|
|
||||||
|
io->Init(); |
||||||
|
comms->Init(); |
||||||
|
display->Init(); |
||||||
|
|
||||||
|
esp_timer_create_args_t timer_args; |
||||||
|
timer_args.callback = UGV_TickTimeout; |
||||||
|
timer_args.arg = this; |
||||||
|
timer_args.dispatch_method = ESP_TIMER_TASK; |
||||||
|
timer_args.name = "ugv_main_loop"; |
||||||
|
esp_timer_create(&timer_args, &this->timer_handle); |
||||||
|
esp_timer_start_periodic(timer_handle, LOOP_PERIOD_US); |
||||||
|
last_print_ = 0; |
||||||
|
last_noise_ = 0; |
||||||
|
last_left_ = 0; |
||||||
|
last_right_ = 0; |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::UpdateAHRS() { |
||||||
|
io::Vec3f &g = inputs_.mpu.gyro_rate, &a = inputs_.mpu.accel, |
||||||
|
&m = inputs_.mpu.mag; |
||||||
|
ahrs_.update(g.x, g.y, g.z, a.x, a.y, a.z, m.x, m.y, m.z); |
||||||
|
yaw_ = ahrs_.getYaw() + conf_.mag_declination(); |
||||||
|
while (yaw_ > 360.) { |
||||||
|
yaw_ -= 360.; |
||||||
|
} |
||||||
|
while (yaw_ < 0.) { |
||||||
|
yaw_ += 360.; |
||||||
|
} |
||||||
|
pitch_ = ahrs_.getPitch(); |
||||||
|
roll_ = ahrs_.getRoll(); |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::DoDebugPrint() { |
||||||
|
auto &mpu = inputs_.mpu; |
||||||
|
#ifdef CALIBRATE |
||||||
|
ESP_LOGD(TAG, "inputs: acc=(%f, %f, %f) gyro=(%f, %f, %f) mag=(%f, %f, %f)", |
||||||
|
mpu.accel.x, mpu.accel.y, mpu.accel.z, mpu.gyro_rate.x, |
||||||
|
mpu.gyro_rate.y, mpu.gyro_rate.z, mpu.mag.x, mpu.mag.y, mpu.mag.z); |
||||||
|
#else |
||||||
|
ESP_LOGD(TAG, "inputs: acc=(%f, %f, %f) gyro=(%f, %f, %f) mag=(%f, %f, %f)", |
||||||
|
mpu.accel.x, mpu.accel.y, mpu.accel.z, mpu.gyro_rate.x, |
||||||
|
mpu.gyro_rate.y, mpu.gyro_rate.z, mpu.mag.x, mpu.mag.y, mpu.mag.z); |
||||||
|
ESP_LOGD(TAG, "ahrs: yaw=%f, pitch=%f, roll=%f", yaw_, pitch_, roll_); |
||||||
|
ESP_LOGV(TAG, "target angle: %f", angle_controller_.Setpoint()); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::ReadComms() { |
||||||
|
comms->Lock(); |
||||||
|
UpdateLocationFromGPS(*(comms->status.mutable_location()), inputs_.gps); |
||||||
|
comms->status.set_yaw_angle(yaw_); |
||||||
|
comms->status.set_pitch_angle(pitch_); |
||||||
|
comms->status.set_roll_angle(roll_); |
||||||
|
comms->status.set_is_still(is_still_); |
||||||
|
UGV_State comms_ugv_state = comms->status.state(); |
||||||
|
TickType_t ticks_since_last_packet = |
||||||
|
(xTaskGetTickCount() - comms->last_packet_tick); |
||||||
|
if (ticks_since_last_packet >= WATCHDOG_TICKS && |
||||||
|
(comms_ugv_state != UGV_State::STATE_IDLE || |
||||||
|
current_state_ != UGV_State::STATE_IDLE)) { |
||||||
|
ESP_LOGW(TAG, "No comms for %f ticks, disabling", |
||||||
|
ticks_since_last_packet * (1000.f / pdMS_TO_TICKS(1000))); |
||||||
|
comms_ugv_state = UGV_State::STATE_IDLE; |
||||||
|
} |
||||||
|
if (comms_ugv_state != current_state_) { |
||||||
|
ESP_LOGI(TAG, "Comms updated UGV state to %d", comms_ugv_state); |
||||||
|
current_state_ = comms_ugv_state; |
||||||
|
} |
||||||
|
if (comms->new_target) { |
||||||
|
SetTarget(*comms->new_target); |
||||||
|
ESP_LOGI(TAG, "Updating target to (%f, %f)", target_.latitude, |
||||||
|
target_.longitude); |
||||||
|
delete comms->new_target; |
||||||
|
comms->new_target = nullptr; |
||||||
|
} |
||||||
|
if (comms->new_config) { |
||||||
|
ESP_LOGI(TAG, "Updating config"); |
||||||
|
SetConfig(*comms->new_config); |
||||||
|
delete comms->new_config; |
||||||
|
comms->new_config = nullptr; |
||||||
|
} |
||||||
|
comms->Unlock(); |
||||||
|
} |
||||||
|
|
||||||
|
void UGV::OnTick() { |
||||||
|
ESP_LOGV(TAG, "OnTick"); |
||||||
|
int64_t time_us = esp_timer_get_time(); |
||||||
|
float time_s = ((float)time_us) / 1e6; |
||||||
|
io->ReadInputs(inputs_); |
||||||
|
UpdateAHRS(); |
||||||
|
|
||||||
|
angle_controller_.Input(yaw_); |
||||||
|
float drive_power = 0.; |
||||||
|
outputs_.left_motor = 0.0; |
||||||
|
outputs_.right_motor = 0.0; |
||||||
|
|
||||||
|
float pitch = roll_; // TODO: fix quaternion -> YPR
|
||||||
|
auto min_flip_pitch = conf_.min_flip_pitch(); |
||||||
|
bool is_upside_down = (pitch > min_flip_pitch) || (pitch < -min_flip_pitch); |
||||||
|
|
||||||
|
io::Vec3f d_accel = inputs_.mpu.accel - last_mpu_.accel; |
||||||
|
io::Vec3f d_gyro = inputs_.mpu.gyro_rate - last_mpu_.gyro_rate; |
||||||
|
last_mpu_ = inputs_.mpu; |
||||||
|
|
||||||
|
accel_noise_accum_ += d_accel.norm2() * LOOP_PERIOD_S; |
||||||
|
gyro_noise_accum_ += d_gyro.norm2() * LOOP_PERIOD_S; |
||||||
|
|
||||||
|
if (time_us >= last_noise_ + NOISE_PERIOD_US) { |
||||||
|
accel_noise_ = accel_noise_accum_ / NOISE_PERIOD_S; |
||||||
|
gyro_noise_ = gyro_noise_accum_ / NOISE_PERIOD_S; |
||||||
|
is_still_ = (accel_noise_ < ACCEL_NOISE_THRESHOLD) && |
||||||
|
(gyro_noise_ < GYRO_NOISE_THRESHOLD); |
||||||
|
ESP_LOGD(TAG, "is still: %s, accel noise: %f, gyro noise: %f", |
||||||
|
is_still_ ? "still" : "moving", accel_noise_, gyro_noise_); |
||||||
|
accel_noise_accum_ = 0; |
||||||
|
gyro_noise_accum_ = 0; |
||||||
|
last_noise_ = time_us; |
||||||
|
} |
||||||
|
|
||||||
|
ReadComms(); |
||||||
|
next_state_ = current_state_; |
||||||
|
|
||||||
|
switch (current_state_) { |
||||||
|
default: |
||||||
|
ESP_LOGW(TAG, "unhandled state: %d", current_state_); |
||||||
|
// fall through
|
||||||
|
case UGV_State::STATE_IDLE: |
||||||
|
case UGV_State::STATE_FINISHED: angle_controller_.Disable(); break; |
||||||
|
case UGV_State::STATE_AQUIRING: { |
||||||
|
if (is_upside_down) { |
||||||
|
next_state_ = UGV_State::STATE_FLIPPING; |
||||||
|
break; |
||||||
|
} |
||||||
|
angle_controller_.Disable(); |
||||||
|
TickType_t current_tick = xTaskGetTickCount(); |
||||||
|
TickType_t ticks_since_gps = current_tick - inputs_.gps.last_update; |
||||||
|
bool not_old = ticks_since_gps <= pdMS_TO_TICKS(2000); |
||||||
|
bool not_invalid = inputs_.gps.fix_quality != io::GPS_FIX_INVALID; |
||||||
|
if (not_old && not_invalid) { |
||||||
|
next_state_ = UGV_State::STATE_TURNING; |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
case UGV_State::STATE_FLIPPING: { |
||||||
|
angle_controller_.Disable(); |
||||||
|
outputs_.left_motor = 0.8; |
||||||
|
outputs_.right_motor = 0.8; |
||||||
|
if (!is_upside_down) { |
||||||
|
next_state_ = UGV_State::STATE_AQUIRING; |
||||||
|
break; |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
case UGV_State::STATE_TURNING: { |
||||||
|
if (is_upside_down) { |
||||||
|
next_state_ = UGV_State::STATE_FLIPPING; |
||||||
|
break; |
||||||
|
} |
||||||
|
if (inputs_.gps.fix_quality == io::GPS_FIX_INVALID) { |
||||||
|
next_state_ = UGV_State::STATE_AQUIRING; |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
LatLong current_pos = {inputs_.gps.latitude, inputs_.gps.longitude}; |
||||||
|
float tgt_bearing = current_pos.bearing_toward(target_); |
||||||
|
angle_controller_.Enable(); |
||||||
|
angle_controller_.Setpoint(tgt_bearing); |
||||||
|
|
||||||
|
if (fabs(angle_controller_.Error()) <= 5.0) { |
||||||
|
next_state_ = UGV_State::STATE_DRIVING; |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
case UGV_State::STATE_DRIVING: { |
||||||
|
if (is_upside_down) { |
||||||
|
next_state_ = UGV_State::STATE_FLIPPING; |
||||||
|
break; |
||||||
|
} |
||||||
|
if (inputs_.gps.fix_quality == io::GPS_FIX_INVALID) { |
||||||
|
next_state_ = UGV_State::STATE_AQUIRING; |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
LatLong current_pos = {inputs_.gps.latitude, inputs_.gps.longitude}; |
||||||
|
float tgt_dist = current_pos.distance_to(target_); |
||||||
|
|
||||||
|
if (tgt_dist <= conf_.min_target_dist()) { |
||||||
|
ESP_LOGI(TAG, "Finished driving to target"); |
||||||
|
next_state_ = UGV_State::STATE_FINISHED; |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
float tgt_bearing = current_pos.bearing_toward(target_); |
||||||
|
angle_controller_.Enable(); |
||||||
|
angle_controller_.Setpoint(tgt_bearing); |
||||||
|
drive_power = conf_.drive_power(); |
||||||
|
break; |
||||||
|
} |
||||||
|
case UGV_State::STATE_TEST: |
||||||
|
#define BASIC_TEST |
||||||
|
#ifdef BASIC_TEST |
||||||
|
outputs_.left_motor = sinf(time_s * PI); |
||||||
|
outputs_.right_motor = cosf(time_s * PI); |
||||||
|
#else |
||||||
|
angle_controller_.Enable(); |
||||||
|
angle_controller_.Setpoint(90.0); |
||||||
|
#endif |
||||||
|
break; |
||||||
|
case UGV_State::STATE_DRIVE_HEADING: |
||||||
|
angle_controller_.Enable(); |
||||||
|
angle_controller_.Setpoint(comms->drive_heading.heading()); |
||||||
|
drive_power = comms->drive_heading.power(); |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
if (angle_controller_.Enabled()) { |
||||||
|
float angle_pwr = angle_controller_.Update(); |
||||||
|
outputs_.left_motor = drive_power - angle_pwr; |
||||||
|
outputs_.right_motor = drive_power + angle_pwr; |
||||||
|
} |
||||||
|
|
||||||
|
constexpr float MAX_ACCEL = 16 * LOOP_PERIOD_S; |
||||||
|
|
||||||
|
if (inputs_.mpu.gyro_rate.x == 0 && inputs_.mpu.gyro_rate.y == 0 && |
||||||
|
inputs_.mpu.gyro_rate.z == 0) { |
||||||
|
outputs_.left_motor = 0; |
||||||
|
outputs_.right_motor = 0; |
||||||
|
did_miss_mpu_ = true; |
||||||
|
} else { |
||||||
|
float dleft = outputs_.left_motor - last_left_; |
||||||
|
float dright = outputs_.right_motor - last_right_; |
||||||
|
if (dleft > MAX_ACCEL) { |
||||||
|
outputs_.left_motor = last_left_ + MAX_ACCEL; |
||||||
|
} else if (dleft < -MAX_ACCEL) { |
||||||
|
outputs_.left_motor = last_left_ - MAX_ACCEL; |
||||||
|
} |
||||||
|
if (dright > MAX_ACCEL) { |
||||||
|
outputs_.right_motor = last_right_ + MAX_ACCEL; |
||||||
|
} else if (dright < -MAX_ACCEL) { |
||||||
|
outputs_.right_motor = last_right_ - MAX_ACCEL; |
||||||
|
} |
||||||
|
} |
||||||
|
io->WriteOutputs(outputs_); |
||||||
|
last_left_ = outputs_.left_motor; |
||||||
|
last_right_ = outputs_.right_motor; |
||||||
|
|
||||||
|
if (current_state_ != next_state_) { |
||||||
|
ESP_LOGI(TAG, "switching state to %d", next_state_); |
||||||
|
} |
||||||
|
comms->Lock(); |
||||||
|
comms->status.set_state(next_state_); |
||||||
|
comms->Unlock(); |
||||||
|
|
||||||
|
#ifdef CALIBRATE |
||||||
|
const long debug_print_period = 50 * 1000; |
||||||
|
#else |
||||||
|
const long debug_print_period = 500 * 1000; |
||||||
|
#endif |
||||||
|
|
||||||
|
if (time_us >= last_print_ + debug_print_period) { |
||||||
|
if (did_miss_mpu_) { |
||||||
|
ESP_LOGW(TAG, "no MPU data, disabling"); |
||||||
|
did_miss_mpu_ = false; |
||||||
|
} |
||||||
|
DoDebugPrint(); |
||||||
|
last_print_ = time_us; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
UGV *the_ugv; |
||||||
|
|
||||||
|
void Start(void) { |
||||||
|
ESP_LOGI(TAG, "Starting UAS UGV"); |
||||||
|
the_ugv = new UGV(); |
||||||
|
the_ugv->Init(); |
||||||
|
ESP_LOGI(TAG, "Setup finished"); |
||||||
|
} |
||||||
|
|
||||||
|
} // namespace ugv
|
@ -0,0 +1,81 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <esp_log.h> |
||||||
|
#include <esp_timer.h> |
||||||
|
|
||||||
|
#include "MadgwickAHRS.h" |
||||||
|
#include "config.pb.h" |
||||||
|
#include "lat_long.hh" |
||||||
|
#include "pid_controller.hh" |
||||||
|
#include "ugv_io.hh" |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
|
||||||
|
namespace comms { |
||||||
|
class CommsClass; |
||||||
|
} |
||||||
|
|
||||||
|
class DisplayClass; |
||||||
|
|
||||||
|
using ugv::comms::CommsClass; |
||||||
|
using ugv::comms::messages::UGV_State; |
||||||
|
using ugv::io::IOClass; |
||||||
|
|
||||||
|
extern "C" void UGV_TickTimeout(void *arg); |
||||||
|
|
||||||
|
void UpdateLocationFromGPS(comms::messages::Location &location, |
||||||
|
const io::GpsData &gps_data); |
||||||
|
|
||||||
|
class UGV { |
||||||
|
private: |
||||||
|
CommsClass *comms; |
||||||
|
IOClass *io; |
||||||
|
DisplayClass *display; |
||||||
|
esp_timer_handle_t timer_handle; |
||||||
|
|
||||||
|
LatLong target_; |
||||||
|
config::Config conf_; |
||||||
|
PIDController angle_controller_; |
||||||
|
Madgwick ahrs_; |
||||||
|
|
||||||
|
io::Inputs inputs_; |
||||||
|
io::Outputs outputs_; |
||||||
|
int64_t last_print_; |
||||||
|
UGV_State current_state_; |
||||||
|
UGV_State next_state_; |
||||||
|
float yaw_; |
||||||
|
float pitch_; |
||||||
|
float roll_; |
||||||
|
io::MpuData last_mpu_; |
||||||
|
int64_t last_noise_; |
||||||
|
float accel_noise_accum_; |
||||||
|
float gyro_noise_accum_; |
||||||
|
float accel_noise_; |
||||||
|
float gyro_noise_; |
||||||
|
bool is_still_; |
||||||
|
float last_left_; |
||||||
|
float last_right_; |
||||||
|
bool did_miss_mpu_; |
||||||
|
|
||||||
|
void UpdateAHRS(); |
||||||
|
void DoDebugPrint(); |
||||||
|
void ReadComms(); |
||||||
|
|
||||||
|
public: |
||||||
|
explicit UGV(); |
||||||
|
|
||||||
|
static config::Config DefaultConfig(); |
||||||
|
|
||||||
|
void SetConfig(const config::Config &conf); |
||||||
|
void SetTarget(LatLong target); |
||||||
|
|
||||||
|
void Init(); |
||||||
|
|
||||||
|
void OnTick(); |
||||||
|
}; |
||||||
|
|
||||||
|
extern UGV *the_ugv; |
||||||
|
|
||||||
|
void Start(void); |
||||||
|
|
||||||
|
} // namespace ugv
|
@ -1,32 +0,0 @@ |
|||||||
#pragma once |
|
||||||
|
|
||||||
#include <freertos/FreeRTOS.h> |
|
||||||
#include <freertos/semphr.h> |
|
||||||
#include <freertos/task.h> |
|
||||||
|
|
||||||
#include "messages.pb.h" |
|
||||||
#include "sx127x_driver.h" |
|
||||||
|
|
||||||
#ifdef __cplusplus |
|
||||||
extern "C" { |
|
||||||
#endif |
|
||||||
|
|
||||||
typedef struct ugv_comms_state_s { |
|
||||||
sx127x_hndl lora; |
|
||||||
TaskHandle_t task_handle; |
|
||||||
|
|
||||||
SemaphoreHandle_t mutex; |
|
||||||
uas::ugv::Location location; |
|
||||||
uas::ugv::UGV_State ugv_state; |
|
||||||
TickType_t last_packet_tick; |
|
||||||
int32_t last_packet_rssi; |
|
||||||
int8_t last_packet_snr; |
|
||||||
} ugv_comms_state_t; |
|
||||||
|
|
||||||
extern ugv_comms_state_t ugv_comms_state; |
|
||||||
|
|
||||||
void ugv_comms_init(); |
|
||||||
|
|
||||||
#ifdef __cplusplus |
|
||||||
} |
|
||||||
#endif |
|
@ -0,0 +1,78 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <freertos/FreeRTOS.h> |
||||||
|
#include <freertos/semphr.h> |
||||||
|
#include <freertos/task.h> |
||||||
|
|
||||||
|
#include "messages.pb.h" |
||||||
|
|
||||||
|
#ifdef COMMS_SX127X |
||||||
|
#include "sx127x_driver.h" |
||||||
|
#else |
||||||
|
#include "e32_driver.hh" |
||||||
|
#endif |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
namespace comms { |
||||||
|
|
||||||
|
namespace messages = ugv::messages; |
||||||
|
namespace config = ugv::config; |
||||||
|
|
||||||
|
class CommsClass { |
||||||
|
public: |
||||||
|
static constexpr int MAX_PACKET_LEN = 128; |
||||||
|
static constexpr TickType_t PACKET_RX_TIMEOUT = pdMS_TO_TICKS(200); |
||||||
|
|
||||||
|
CommsClass(); |
||||||
|
|
||||||
|
void Init(); |
||||||
|
|
||||||
|
void Lock(TickType_t ticks_to_wait = pdMS_TO_TICKS(1000)); |
||||||
|
void Unlock(); |
||||||
|
|
||||||
|
int32_t ReadRssi(); |
||||||
|
uint8_t ReadLnaGain(); |
||||||
|
|
||||||
|
public: |
||||||
|
SemaphoreHandle_t mutex; |
||||||
|
TickType_t last_packet_tick; |
||||||
|
int32_t last_packet_rssi; |
||||||
|
int8_t last_packet_snr; |
||||||
|
|
||||||
|
messages::UGV_Status status; |
||||||
|
messages::DriveHeadingData drive_heading; |
||||||
|
messages::TargetLocation* new_target; |
||||||
|
config::Config* new_config; |
||||||
|
|
||||||
|
private: |
||||||
|
#ifdef COMMS_SX127X |
||||||
|
sx127x_hndl lora; |
||||||
|
#else |
||||||
|
e32::E32_Driver lora; |
||||||
|
#endif |
||||||
|
TaskHandle_t task_handle; |
||||||
|
|
||||||
|
messages::UGV_Message status_message; |
||||||
|
std::string status_message_data; |
||||||
|
TickType_t next_status_send; |
||||||
|
|
||||||
|
void RunTask(); |
||||||
|
|
||||||
|
#ifdef COMMS_SX127X |
||||||
|
void HandlePacket(sx127x_rx_packet_t* packet); |
||||||
|
#endif |
||||||
|
|
||||||
|
void HandlePacket(const uint8_t* data, size_t size); |
||||||
|
void HandleCommand(const messages::GroundCommand& command); |
||||||
|
|
||||||
|
esp_err_t SendPacket(const uint8_t* data, size_t size); |
||||||
|
esp_err_t SendPacket(const std::string& str); |
||||||
|
esp_err_t SendPacket(const google::protobuf::MessageLite& message); |
||||||
|
|
||||||
|
void SendStatus(); |
||||||
|
|
||||||
|
static void CommsTask(void* arg); |
||||||
|
}; |
||||||
|
|
||||||
|
} // namespace comms
|
||||||
|
} // namespace ugv
|
@ -0,0 +1,105 @@ |
|||||||
|
#include "ugv_display.hh" |
||||||
|
|
||||||
|
#include <esp_log.h> |
||||||
|
#include "U8g2lib.hh" |
||||||
|
#include "ugv_comms.hh" |
||||||
|
#include "ugv_config.h" |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
|
||||||
|
static const char* TAG = "ugv_display"; |
||||||
|
|
||||||
|
using comms::CommsClass; |
||||||
|
|
||||||
|
DisplayClass::DisplayClass(CommsClass* comms) : comms_(comms) {} |
||||||
|
|
||||||
|
void DisplayClass::Init() { |
||||||
|
ESP_LOGD(TAG, "Initializing u8g2 display"); |
||||||
|
// For Heltec ESP32 LoRa
|
||||||
|
// oled = new U8G2_SSD1306_128X64_NONAME_F_HW_I2C(U8G2_R0, 16, 15, 4);
|
||||||
|
// For wemos Lolin ESP32
|
||||||
|
oled = new U8G2_SSD1306_128X64_NONAME_F_HW_I2C(U8G2_R0, OLED_RESET, |
||||||
|
OLED_CLOCK, OLED_DATA); |
||||||
|
oled->initDisplay(); |
||||||
|
oled->clearDisplay(); |
||||||
|
oled->setPowerSave(false); |
||||||
|
|
||||||
|
BaseType_t xRet = xTaskCreate(DisplayClass::RunThread, "ugv_display", |
||||||
|
8 * 1024, this, 1, &this->task_handle_); |
||||||
|
if (xRet != pdTRUE) { |
||||||
|
ESP_LOGE(TAG, "error starting display thread"); |
||||||
|
return; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void DisplayClass::Run() { |
||||||
|
#ifdef COMMS_SX127X |
||||||
|
int32_t lora_rssi; |
||||||
|
uint8_t lora_lna_gain; |
||||||
|
int32_t last_packet_rssi; |
||||||
|
int8_t last_packet_snr; |
||||||
|
#endif |
||||||
|
TickType_t last_packet_tick; |
||||||
|
messages::UGV_Status status; |
||||||
|
|
||||||
|
ESP_LOGD(TAG, "Started display thread"); |
||||||
|
while (true) { |
||||||
|
oled->firstPage(); |
||||||
|
#ifdef COMMS_SX127X |
||||||
|
lora_rssi = comms_->ReadRssi(); |
||||||
|
lora_lna_gain = comms_->ReadLnaGain(); |
||||||
|
#endif |
||||||
|
|
||||||
|
comms_->Lock(); |
||||||
|
last_packet_tick = comms_->last_packet_tick; |
||||||
|
status.CopyFrom(comms_->status); |
||||||
|
#ifdef COMMS_SX127X |
||||||
|
last_packet_rssi = comms_->last_packet_rssi; |
||||||
|
last_packet_snr = comms_->last_packet_snr; |
||||||
|
#endif |
||||||
|
comms_->Unlock(); |
||||||
|
do { |
||||||
|
oled->drawRFrame(0, 0, OLED_W, OLED_H, 4); |
||||||
|
|
||||||
|
multi_heap_info_t heap_info; |
||||||
|
heap_caps_get_info(&heap_info, MALLOC_CAP_DEFAULT); |
||||||
|
oled->setFont(u8g2_font_4x6_mr); |
||||||
|
oled->setCursor(4, 8); |
||||||
|
oled->print("=====UAS UGV====="); |
||||||
|
oled->setCursor(4, 2 * 8); |
||||||
|
oled->printf("heap allc/free %d/%d", heap_info.total_allocated_bytes, |
||||||
|
heap_info.total_free_bytes); |
||||||
|
|
||||||
|
oled->setCursor(4, 3 * 8); |
||||||
|
oled->printf("state: %d", status.state()); |
||||||
|
|
||||||
|
if (last_packet_tick > 0) { |
||||||
|
double time_since_last_packet = |
||||||
|
static_cast<float>((xTaskGetTickCount() - last_packet_tick) * |
||||||
|
portTICK_RATE_MS) / |
||||||
|
1000.f; |
||||||
|
oled->setCursor(4, 4 * 8); |
||||||
|
oled->printf("last pkt rx %.2f s ago", time_since_last_packet); |
||||||
|
#ifdef COMMS_SX127X |
||||||
|
oled->setCursor(4, 5 * 8); |
||||||
|
oled->printf("pkt rssi: %d, snr: %f", last_packet_rssi, |
||||||
|
last_packet_snr * 0.25f); |
||||||
|
#endif |
||||||
|
} else { |
||||||
|
oled->setCursor(4, 4 * 8); |
||||||
|
oled->print("no pkt rx"); |
||||||
|
} |
||||||
|
oled->setCursor(4, 5 * 8); |
||||||
|
oled->printf("yaw angle: %f", status.yaw_angle()); |
||||||
|
} while (oled->nextPage()); |
||||||
|
vTaskDelay(pdMS_TO_TICKS(1000)); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void DisplayClass::RunThread(void* arg) { |
||||||
|
auto display = (DisplayClass*)arg; |
||||||
|
display->Run(); |
||||||
|
vTaskDelete(NULL); |
||||||
|
} |
||||||
|
|
||||||
|
} // namespace ugv
|
@ -0,0 +1,30 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <freertos/FreeRTOS.h> |
||||||
|
#include <freertos/task.h> |
||||||
|
|
||||||
|
class U8G2; |
||||||
|
|
||||||
|
namespace ugv { |
||||||
|
|
||||||
|
namespace comms { |
||||||
|
class CommsClass; |
||||||
|
} |
||||||
|
|
||||||
|
class DisplayClass { |
||||||
|
public: |
||||||
|
DisplayClass() = delete; |
||||||
|
DisplayClass(comms::CommsClass *comms); |
||||||
|
|
||||||
|
void Init(); |
||||||
|
|
||||||
|
private: |
||||||
|
comms::CommsClass *comms_; |
||||||
|
U8G2 *oled; |
||||||
|
TaskHandle_t task_handle_; |
||||||
|
|
||||||
|
void Run(); |
||||||
|
static void RunThread(void *arg); |
||||||
|
}; |
||||||
|
|
||||||
|
} // namespace ugv
|
@ -1,100 +1,11 @@ |
|||||||
#include <esp_log.h> |
#include "i2c_mutex.h" |
||||||
#include <string.h> |
#include "ugv.hh" |
||||||
#include <u8g2.h> |
|
||||||
|
|
||||||
#include "U8g2lib.hh" |
extern "C" { |
||||||
#include "sx127x_driver.h" |
SemaphoreHandle_t i2c_mutex; |
||||||
#include "sx127x_registers.h" |
|
||||||
#include "ugv_comms.h" |
|
||||||
#include "ugv_config.h" |
|
||||||
#include "ugv_io.hh" |
|
||||||
|
|
||||||
namespace ugv { |
|
||||||
|
|
||||||
using ugv::io::IO; |
|
||||||
|
|
||||||
static const char *TAG = "ugv_main"; |
|
||||||
|
|
||||||
U8G2 *oled; |
|
||||||
|
|
||||||
void setup_oled(void) { |
|
||||||
oled = new U8G2_SSD1306_128X64_NONAME_F_HW_I2C(U8G2_R0, 16, 15, 4); |
|
||||||
oled->initDisplay(); |
|
||||||
oled->clearDisplay(); |
|
||||||
oled->setPowerSave(false); |
|
||||||
} |
} |
||||||
|
|
||||||
void setup(void) { |
|
||||||
ESP_LOGI(TAG, "setup"); |
|
||||||
|
|
||||||
setup_oled(); |
|
||||||
ugv_comms_init(); |
|
||||||
IO.Init(); |
|
||||||
} |
|
||||||
|
|
||||||
#define BUF_SZ 32 |
|
||||||
|
|
||||||
void loop(void) { |
|
||||||
static int32_t lora_rssi; |
|
||||||
static uint8_t lora_lna_gain; |
|
||||||
static TickType_t last_packet_tick; |
|
||||||
static int32_t last_packet_rssi; |
|
||||||
static int8_t last_packet_snr; |
|
||||||
|
|
||||||
static char buf[BUF_SZ]; |
|
||||||
static io::Inputs inputs; |
|
||||||
|
|
||||||
IO.ReadInputs(inputs); |
|
||||||
// ESP_LOGI(TAG, "inputs %s", inputs.ToString());
|
|
||||||
|
|
||||||
oled->firstPage(); |
|
||||||
sx127x_read_rssi(ugv_comms_state.lora, &lora_rssi); |
|
||||||
sx127x_read_lna_gain(ugv_comms_state.lora, &lora_lna_gain); |
|
||||||
|
|
||||||
xSemaphoreTake(ugv_comms_state.mutex, portMAX_DELAY); |
|
||||||
last_packet_tick = ugv_comms_state.last_packet_tick; |
|
||||||
last_packet_rssi = ugv_comms_state.last_packet_rssi; |
|
||||||
last_packet_snr = ugv_comms_state.last_packet_snr; |
|
||||||
xSemaphoreGive(ugv_comms_state.mutex); |
|
||||||
do { |
|
||||||
oled->drawRFrame(0, 0, OLED_W, OLED_H, 4); |
|
||||||
|
|
||||||
multi_heap_info_t heap_info; |
|
||||||
heap_caps_get_info(&heap_info, MALLOC_CAP_DEFAULT); |
|
||||||
oled->setFont(u8g2_font_4x6_mr); |
|
||||||
oled->drawStr(4, 8, "=====UAS UGV====="); |
|
||||||
snprintf(buf, BUF_SZ, "heap allc/free %d/%d", |
|
||||||
heap_info.total_allocated_bytes, heap_info.total_free_bytes); |
|
||||||
oled->drawStr(4, 2 * 8, buf); |
|
||||||
|
|
||||||
snprintf(buf, BUF_SZ, "rssi: %d lna gain: %d", lora_rssi, lora_lna_gain); |
|
||||||
oled->drawStr(4, 3 * 8, buf); |
|
||||||
|
|
||||||
if (last_packet_tick > 0) { |
|
||||||
double time_since_last_packet = |
|
||||||
1000.0f / |
|
||||||
((xTaskGetTickCount() - last_packet_tick) * portTICK_RATE_MS); |
|
||||||
snprintf(buf, BUF_SZ, "last pkt rx %f s ago", time_since_last_packet); |
|
||||||
oled->drawStr(4, 4 * 8, buf); |
|
||||||
snprintf(buf, BUF_SZ, "pkt rssi: %d, snr: %f", last_packet_rssi, |
|
||||||
last_packet_snr * 0.25f); |
|
||||||
oled->drawStr(4, 5 * 8, buf); |
|
||||||
} else { |
|
||||||
oled->drawStr(4, 4 * 8, "no pkt rx"); |
|
||||||
} |
|
||||||
} while (oled->nextPage()); |
|
||||||
vTaskDelay(pdMS_TO_TICKS(1000)); |
|
||||||
} |
|
||||||
|
|
||||||
void loopTask(void *pvUser) { |
|
||||||
setup(); |
|
||||||
while (1) { |
|
||||||
loop(); |
|
||||||
} |
|
||||||
} |
|
||||||
|
|
||||||
} // namespace ugv
|
|
||||||
|
|
||||||
extern "C" void app_main() { |
extern "C" void app_main() { |
||||||
xTaskCreatePinnedToCore(ugv::loopTask, "loopTask", 8192, NULL, 1, NULL, 1); |
i2c_mutex = xSemaphoreCreateMutex(); |
||||||
|
ugv::Start(); |
||||||
} |
} |
||||||
|
@ -0,0 +1,632 @@ |
|||||||
|
# |
||||||
|
# Automatically generated file; DO NOT EDIT. |
||||||
|
# Espressif IoT Development Framework Configuration |
||||||
|
# |
||||||
|
|
||||||
|
# |
||||||
|
# SDK tool configuration |
||||||
|
# |
||||||
|
CONFIG_TOOLPREFIX="xtensa-esp32-elf-" |
||||||
|
CONFIG_MAKE_WARN_UNDEFINED_VARIABLES=y |
||||||
|
|
||||||
|
# |
||||||
|
# Example Configuration |
||||||
|
# |
||||||
|
CONFIG_LCD_TYPE_AUTO=y |
||||||
|
CONFIG_LCD_TYPE_ST7789V= |
||||||
|
CONFIG_LCD_TYPE_ILI9341= |
||||||
|
CONFIG_LCD_OVERCLOCK= |
||||||
|
|
||||||
|
# |
||||||
|
# SX127X Driver Configuration |
||||||
|
# |
||||||
|
CONFIG_SX127X_TASK_STACK_SIZE=2048 |
||||||
|
CONFIG_SX127X_TASK_PRIORITY=3 |
||||||
|
CONFIG_SX127X_RX_QUEUE_LEN=8 |
||||||
|
CONFIG_SX127X_TX_QUEUE_LEN=8 |
||||||
|
CONFIG_SX127X_SPI_CLOCK_HZ=8000000 |
||||||
|
CONFIG_SX127X_SPI_QUEUE_SIZE=8 |
||||||
|
CONFIG_SX127X_SPI_DMA_CHAN=1 |
||||||
|
CONFIG_SX127X_USE_NANOPB=y |
||||||
|
|
||||||
|
# |
||||||
|
# MPU driver |
||||||
|
# |
||||||
|
CONFIG_MPU6000= |
||||||
|
CONFIG_MPU6050= |
||||||
|
CONFIG_MPU6500= |
||||||
|
CONFIG_MPU6555= |
||||||
|
CONFIG_MPU9150= |
||||||
|
CONFIG_MPU9250= |
||||||
|
CONFIG_MPU9255=y |
||||||
|
CONFIG_MPU_CHIP_MODEL="MPU9255" |
||||||
|
CONFIG_MPU_AK8963=y |
||||||
|
CONFIG_MPU_AK89xx=y |
||||||
|
CONFIG_MPU_I2C=y |
||||||
|
CONFIG_MPU_SPI= |
||||||
|
CONFIG_MPU_COMM_PROTOCOL="I2C" |
||||||
|
CONFIG_MPU_LOG_LEVEL_DEFAULT=y |
||||||
|
CONFIG_MPU_LOG_LEVEL_NONE= |
||||||
|
CONFIG_MPU_LOG_LEVEL_ERROR= |
||||||
|
CONFIG_MPU_LOG_LEVEL_WARN= |
||||||
|
CONFIG_MPU_LOG_LEVEL_INFO= |
||||||
|
CONFIG_MPU_LOG_LEVEL_DEBUG= |
||||||
|
CONFIG_MPU_LOG_LEVEL=4 |
||||||
|
CONFIG_MPU_ENABLE_DMP= |
||||||
|
CONFIG_MPU_LOG_ERROR_TRACES=y |
||||||
|
|
||||||
|
# |
||||||
|
# I2Cbus |
||||||
|
# |
||||||
|
CONFIG_I2CBUS_LOG_ERRORS=y |
||||||
|
CONFIG_I2CBUS_LOG_READWRITES= |
||||||
|
|
||||||
|
# |
||||||
|
# Bootloader config |
||||||
|
# |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_NONE= |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_ERROR= |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_WARN=y |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_INFO= |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG= |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE= |
||||||
|
CONFIG_LOG_BOOTLOADER_LEVEL=2 |
||||||
|
CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_8V= |
||||||
|
CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y |
||||||
|
CONFIG_BOOTLOADER_FACTORY_RESET= |
||||||
|
CONFIG_BOOTLOADER_APP_TEST= |
||||||
|
|
||||||
|
# |
||||||
|
# Security features |
||||||
|
# |
||||||
|
CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT= |
||||||
|
CONFIG_SECURE_BOOT_ENABLED= |
||||||
|
CONFIG_FLASH_ENCRYPTION_ENABLED= |
||||||
|
|
||||||
|
# |
||||||
|
# Serial flasher config |
||||||
|
# |
||||||
|
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200 |
||||||
|
CONFIG_FLASHMODE_QIO= |
||||||
|
CONFIG_FLASHMODE_QOUT= |
||||||
|
CONFIG_FLASHMODE_DIO=y |
||||||
|
CONFIG_FLASHMODE_DOUT= |
||||||
|
CONFIG_ESPTOOLPY_FLASHMODE="dio" |
||||||
|
CONFIG_ESPTOOLPY_FLASHFREQ_80M=y |
||||||
|
CONFIG_ESPTOOLPY_FLASHFREQ_40M= |
||||||
|
CONFIG_ESPTOOLPY_FLASHFREQ_26M= |
||||||
|
CONFIG_ESPTOOLPY_FLASHFREQ_20M= |
||||||
|
CONFIG_ESPTOOLPY_FLASHFREQ="80m" |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_1MB= |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_2MB= |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_8MB= |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_16MB= |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE="4MB" |
||||||
|
CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y |
||||||
|
CONFIG_ESPTOOLPY_BEFORE_RESET=y |
||||||
|
CONFIG_ESPTOOLPY_BEFORE_NORESET= |
||||||
|
CONFIG_ESPTOOLPY_BEFORE="default_reset" |
||||||
|
CONFIG_ESPTOOLPY_AFTER_RESET=y |
||||||
|
CONFIG_ESPTOOLPY_AFTER_NORESET= |
||||||
|
CONFIG_ESPTOOLPY_AFTER="hard_reset" |
||||||
|
CONFIG_MONITOR_BAUD_9600B= |
||||||
|
CONFIG_MONITOR_BAUD_57600B= |
||||||
|
CONFIG_MONITOR_BAUD_115200B=y |
||||||
|
CONFIG_MONITOR_BAUD_230400B= |
||||||
|
CONFIG_MONITOR_BAUD_921600B= |
||||||
|
CONFIG_MONITOR_BAUD_2MB= |
||||||
|
CONFIG_MONITOR_BAUD_OTHER= |
||||||
|
CONFIG_MONITOR_BAUD_OTHER_VAL=115200 |
||||||
|
CONFIG_MONITOR_BAUD=115200 |
||||||
|
|
||||||
|
# |
||||||
|
# Partition Table |
||||||
|
# |
||||||
|
CONFIG_PARTITION_TABLE_SINGLE_APP=y |
||||||
|
CONFIG_PARTITION_TABLE_TWO_OTA= |
||||||
|
CONFIG_PARTITION_TABLE_CUSTOM= |
||||||
|
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv" |
||||||
|
CONFIG_PARTITION_TABLE_FILENAME="partitions_singleapp.csv" |
||||||
|
CONFIG_PARTITION_TABLE_OFFSET=0x8000 |
||||||
|
CONFIG_PARTITION_TABLE_MD5=y |
||||||
|
|
||||||
|
# |
||||||
|
# Compiler options |
||||||
|
# |
||||||
|
CONFIG_OPTIMIZATION_LEVEL_DEBUG=y |
||||||
|
CONFIG_OPTIMIZATION_LEVEL_RELEASE= |
||||||
|
CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y |
||||||
|
CONFIG_OPTIMIZATION_ASSERTIONS_SILENT= |
||||||
|
CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED= |
||||||
|
CONFIG_CXX_EXCEPTIONS= |
||||||
|
CONFIG_STACK_CHECK_NONE= |
||||||
|
CONFIG_STACK_CHECK_NORM= |
||||||
|
CONFIG_STACK_CHECK_STRONG=y |
||||||
|
CONFIG_STACK_CHECK_ALL= |
||||||
|
CONFIG_STACK_CHECK=y |
||||||
|
CONFIG_WARN_WRITE_STRINGS=y |
||||||
|
|
||||||
|
# |
||||||
|
# Component config |
||||||
|
# |
||||||
|
|
||||||
|
# |
||||||
|
# MPU driver |
||||||
|
# |
||||||
|
|
||||||
|
# |
||||||
|
# I2Cbus |
||||||
|
# |
||||||
|
|
||||||
|
# |
||||||
|
# Driver configurations |
||||||
|
# |
||||||
|
|
||||||
|
# |
||||||
|
# ADC configuration |
||||||
|
# |
||||||
|
CONFIG_ADC_FORCE_XPD_FSM= |
||||||
|
CONFIG_ADC2_DISABLE_DAC=y |
||||||
|
|
||||||
|
# |
||||||
|
# SPI master configuration |
||||||
|
# |
||||||
|
CONFIG_SPI_MASTER_IN_IRAM= |
||||||
|
CONFIG_SPI_MASTER_ISR_IN_IRAM=y |
||||||
|
|
||||||
|
# |
||||||
|
# Application Level Tracing |
||||||
|
# |
||||||
|
CONFIG_ESP32_APPTRACE_DEST_TRAX= |
||||||
|
CONFIG_ESP32_APPTRACE_DEST_NONE=y |
||||||
|
CONFIG_ESP32_APPTRACE_ENABLE= |
||||||
|
CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y |
||||||
|
|
||||||
|
# |
||||||
|
# SPI Flash driver |
||||||
|
# |
||||||
|
CONFIG_SPI_FLASH_VERIFY_WRITE= |
||||||
|
CONFIG_SPI_FLASH_ENABLE_COUNTERS= |
||||||
|
CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y |
||||||
|
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y |
||||||
|
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS= |
||||||
|
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED= |
||||||
|
|
||||||
|
# |
||||||
|
# mbedTLS |
||||||
|
# |
||||||
|
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384 |
||||||
|
CONFIG_MBEDTLS_DEBUG= |
||||||
|
CONFIG_MBEDTLS_HARDWARE_AES=y |
||||||
|
CONFIG_MBEDTLS_HARDWARE_MPI= |
||||||
|
CONFIG_MBEDTLS_HARDWARE_SHA= |
||||||
|
CONFIG_MBEDTLS_HAVE_TIME=y |
||||||
|
CONFIG_MBEDTLS_HAVE_TIME_DATE= |
||||||
|
CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y |
||||||
|
CONFIG_MBEDTLS_TLS_SERVER_ONLY= |
||||||
|
CONFIG_MBEDTLS_TLS_CLIENT_ONLY= |
||||||
|
CONFIG_MBEDTLS_TLS_DISABLED= |
||||||
|
CONFIG_MBEDTLS_TLS_SERVER=y |
||||||
|
CONFIG_MBEDTLS_TLS_CLIENT=y |
||||||
|
CONFIG_MBEDTLS_TLS_ENABLED=y |
||||||
|
|
||||||
|
# |
||||||
|
# TLS Key Exchange Methods |
||||||
|
# |
||||||
|
CONFIG_MBEDTLS_PSK_MODES= |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y |
||||||
|
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y |
||||||
|
CONFIG_MBEDTLS_SSL_RENEGOTIATION=y |
||||||
|
CONFIG_MBEDTLS_SSL_PROTO_SSL3= |
||||||
|
CONFIG_MBEDTLS_SSL_PROTO_TLS1=y |
||||||
|
CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y |
||||||
|
CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y |
||||||
|
CONFIG_MBEDTLS_SSL_PROTO_DTLS= |
||||||
|
CONFIG_MBEDTLS_SSL_ALPN=y |
||||||
|
CONFIG_MBEDTLS_SSL_SESSION_TICKETS=y |
||||||
|
|
||||||
|
# |
||||||
|
# Symmetric Ciphers |
||||||
|
# |
||||||
|
CONFIG_MBEDTLS_AES_C=y |
||||||
|
CONFIG_MBEDTLS_CAMELLIA_C= |
||||||
|
CONFIG_MBEDTLS_DES_C= |
||||||
|
CONFIG_MBEDTLS_RC4_DISABLED=y |
||||||
|
CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT= |
||||||
|
CONFIG_MBEDTLS_RC4_ENABLED= |
||||||
|
CONFIG_MBEDTLS_BLOWFISH_C= |
||||||
|
CONFIG_MBEDTLS_XTEA_C= |
||||||
|
CONFIG_MBEDTLS_CCM_C=y |
||||||
|
CONFIG_MBEDTLS_GCM_C=y |
||||||
|
CONFIG_MBEDTLS_RIPEMD160_C= |
||||||
|
|
||||||
|
# |
||||||
|
# Certificates |
||||||
|
# |
||||||
|
CONFIG_MBEDTLS_PEM_PARSE_C=y |
||||||
|
CONFIG_MBEDTLS_PEM_WRITE_C=y |
||||||
|
CONFIG_MBEDTLS_X509_CRL_PARSE_C=y |
||||||
|
CONFIG_MBEDTLS_X509_CSR_PARSE_C=y |
||||||
|
CONFIG_MBEDTLS_ECP_C=y |
||||||
|
CONFIG_MBEDTLS_ECDH_C=y |
||||||
|
CONFIG_MBEDTLS_ECDSA_C=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y |
||||||
|
CONFIG_MBEDTLS_ECP_NIST_OPTIM=y |
||||||
|
|
||||||
|
# |
||||||
|
# LWIP |
||||||
|
# |
||||||
|
CONFIG_L2_TO_L3_COPY= |
||||||
|
CONFIG_LWIP_IRAM_OPTIMIZATION= |
||||||
|
CONFIG_LWIP_MAX_SOCKETS=10 |
||||||
|
CONFIG_USE_ONLY_LWIP_SELECT= |
||||||
|
CONFIG_LWIP_SO_REUSE=y |
||||||
|
CONFIG_LWIP_SO_REUSE_RXTOALL=y |
||||||
|
CONFIG_LWIP_SO_RCVBUF= |
||||||
|
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1 |
||||||
|
CONFIG_LWIP_IP_FRAG= |
||||||
|
CONFIG_LWIP_IP_REASSEMBLY= |
||||||
|
CONFIG_LWIP_STATS= |
||||||
|
CONFIG_LWIP_ETHARP_TRUST_IP_MAC= |
||||||
|
CONFIG_ESP_GRATUITOUS_ARP=y |
||||||
|
CONFIG_GARP_TMR_INTERVAL=60 |
||||||
|
CONFIG_TCPIP_RECVMBOX_SIZE=32 |
||||||
|
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y |
||||||
|
|
||||||
|
# |
||||||
|
# DHCP server |
||||||
|
# |
||||||
|
CONFIG_LWIP_DHCPS_LEASE_UNIT=60 |
||||||
|
CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8 |
||||||
|
CONFIG_LWIP_AUTOIP= |
||||||
|
CONFIG_LWIP_NETIF_LOOPBACK=y |
||||||
|
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8 |
||||||
|
|
||||||
|
# |
||||||
|
# TCP |
||||||
|
# |
||||||
|
CONFIG_LWIP_MAX_ACTIVE_TCP=16 |
||||||
|
CONFIG_LWIP_MAX_LISTENING_TCP=16 |
||||||
|
CONFIG_TCP_MAXRTX=12 |
||||||
|
CONFIG_TCP_SYNMAXRTX=6 |
||||||
|
CONFIG_TCP_MSS=1436 |
||||||
|
CONFIG_TCP_MSL=60000 |
||||||
|
CONFIG_TCP_SND_BUF_DEFAULT=5744 |
||||||
|
CONFIG_TCP_WND_DEFAULT=5744 |
||||||
|
CONFIG_TCP_RECVMBOX_SIZE=6 |
||||||
|
CONFIG_TCP_QUEUE_OOSEQ=y |
||||||
|
CONFIG_ESP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES= |
||||||
|
CONFIG_TCP_OVERSIZE_MSS=y |
||||||
|
CONFIG_TCP_OVERSIZE_QUARTER_MSS= |
||||||
|
CONFIG_TCP_OVERSIZE_DISABLE= |
||||||
|
|
||||||
|
# |
||||||
|
# UDP |
||||||
|
# |
||||||
|
CONFIG_LWIP_MAX_UDP_PCBS=16 |
||||||
|
CONFIG_UDP_RECVMBOX_SIZE=6 |
||||||
|
CONFIG_TCPIP_TASK_STACK_SIZE=2560 |
||||||
|
CONFIG_PPP_SUPPORT= |
||||||
|
|
||||||
|
# |
||||||
|
# ICMP |
||||||
|
# |
||||||
|
CONFIG_LWIP_MULTICAST_PING= |
||||||
|
CONFIG_LWIP_BROADCAST_PING= |
||||||
|
|
||||||
|
# |
||||||
|
# LWIP RAW API |
||||||
|
# |
||||||
|
CONFIG_LWIP_MAX_RAW_PCBS=16 |
||||||
|
|
||||||
|
# |
||||||
|
# Virtual file system |
||||||
|
# |
||||||
|
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y |
||||||
|
|
||||||
|
# |
||||||
|
# Ethernet |
||||||
|
# |
||||||
|
CONFIG_DMA_RX_BUF_NUM=10 |
||||||
|
CONFIG_DMA_TX_BUF_NUM=10 |
||||||
|
CONFIG_EMAC_L2_TO_L3_RX_BUF_MODE= |
||||||
|
CONFIG_EMAC_TASK_PRIORITY=20 |
||||||
|
|
||||||
|
# |
||||||
|
# tcpip adapter |
||||||
|
# |
||||||
|
CONFIG_IP_LOST_TIMER_INTERVAL=120 |
||||||
|
CONFIG_AWS_IOT_SDK= |
||||||
|
|
||||||
|
# |
||||||
|
# Bluetooth |
||||||
|
# |
||||||
|
CONFIG_BT_ENABLED= |
||||||
|
CONFIG_BTDM_CONTROLLER_PINNED_TO_CORE=0 |
||||||
|
CONFIG_BT_RESERVE_DRAM=0 |
||||||
|
|
||||||
|
# |
||||||
|
# NVS |
||||||
|
# |
||||||
|
CONFIG_MP_BLOB_SUPPORT= |
||||||
|
|
||||||
|
# |
||||||
|
# ESP32-specific |
||||||
|
# |
||||||
|
CONFIG_ESP32_DEFAULT_CPU_FREQ_80= |
||||||
|
CONFIG_ESP32_DEFAULT_CPU_FREQ_160= |
||||||
|
CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y |
||||||
|
CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 |
||||||
|
CONFIG_SPIRAM_SUPPORT= |
||||||
|
CONFIG_MEMMAP_TRACEMEM= |
||||||
|
CONFIG_MEMMAP_TRACEMEM_TWOBANKS= |
||||||
|
CONFIG_ESP32_TRAX= |
||||||
|
CONFIG_TRACEMEM_RESERVE_DRAM=0x0 |
||||||
|
CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH= |
||||||
|
CONFIG_ESP32_ENABLE_COREDUMP_TO_UART= |
||||||
|
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y |
||||||
|
CONFIG_ESP32_ENABLE_COREDUMP= |
||||||
|
CONFIG_TWO_UNIVERSAL_MAC_ADDRESS= |
||||||
|
CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y |
||||||
|
CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 |
||||||
|
CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32 |
||||||
|
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2304 |
||||||
|
CONFIG_MAIN_TASK_STACK_SIZE=3584 |
||||||
|
CONFIG_IPC_TASK_STACK_SIZE=1024 |
||||||
|
CONFIG_TIMER_TASK_STACK_SIZE=3584 |
||||||
|
CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y |
||||||
|
CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF= |
||||||
|
CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR= |
||||||
|
CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF= |
||||||
|
CONFIG_NEWLIB_STDIN_LINE_ENDING_LF= |
||||||
|
CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y |
||||||
|
CONFIG_NEWLIB_NANO_FORMAT= |
||||||
|
CONFIG_CONSOLE_UART_DEFAULT=y |
||||||
|
CONFIG_CONSOLE_UART_CUSTOM= |
||||||
|
CONFIG_CONSOLE_UART_NONE= |
||||||
|
CONFIG_CONSOLE_UART_NUM=0 |
||||||
|
CONFIG_CONSOLE_UART_BAUDRATE=115200 |
||||||
|
CONFIG_ULP_COPROC_ENABLED= |
||||||
|
CONFIG_ULP_COPROC_RESERVE_MEM=0 |
||||||
|
CONFIG_ESP32_PANIC_PRINT_HALT= |
||||||
|
CONFIG_ESP32_PANIC_PRINT_REBOOT=y |
||||||
|
CONFIG_ESP32_PANIC_SILENT_REBOOT= |
||||||
|
CONFIG_ESP32_PANIC_GDBSTUB= |
||||||
|
CONFIG_ESP32_DEBUG_OCDAWARE=y |
||||||
|
CONFIG_ESP32_DEBUG_STUBS_ENABLE=y |
||||||
|
CONFIG_INT_WDT=y |
||||||
|
CONFIG_INT_WDT_TIMEOUT_MS=300 |
||||||
|
CONFIG_INT_WDT_CHECK_CPU1=y |
||||||
|
CONFIG_TASK_WDT=y |
||||||
|
CONFIG_TASK_WDT_PANIC= |
||||||
|
CONFIG_TASK_WDT_TIMEOUT_S=5 |
||||||
|
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y |
||||||
|
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y |
||||||
|
CONFIG_BROWNOUT_DET=y |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_0=y |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_1= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_2= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_3= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_4= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_5= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_6= |
||||||
|
CONFIG_BROWNOUT_DET_LVL_SEL_7= |
||||||
|
CONFIG_BROWNOUT_DET_LVL=0 |
||||||
|
CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y |
||||||
|
CONFIG_ESP32_TIME_SYSCALL_USE_RTC= |
||||||
|
CONFIG_ESP32_TIME_SYSCALL_USE_FRC1= |
||||||
|
CONFIG_ESP32_TIME_SYSCALL_USE_NONE= |
||||||
|
CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y |
||||||
|
CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL= |
||||||
|
CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 |
||||||
|
CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 |
||||||
|
CONFIG_ESP32_XTAL_FREQ_40=y |
||||||
|
CONFIG_ESP32_XTAL_FREQ_26= |
||||||
|
CONFIG_ESP32_XTAL_FREQ_AUTO= |
||||||
|
CONFIG_ESP32_XTAL_FREQ=40 |
||||||
|
CONFIG_DISABLE_BASIC_ROM_CONSOLE= |
||||||
|
CONFIG_NO_BLOBS= |
||||||
|
CONFIG_ESP_TIMER_PROFILING= |
||||||
|
CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS= |
||||||
|
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y |
||||||
|
|
||||||
|
# |
||||||
|
# Wi-Fi |
||||||
|
# |
||||||
|
CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=10 |
||||||
|
CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=32 |
||||||
|
CONFIG_ESP32_WIFI_STATIC_TX_BUFFER= |
||||||
|
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y |
||||||
|
CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 |
||||||
|
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=32 |
||||||
|
CONFIG_ESP32_WIFI_CSI_ENABLED= |
||||||
|
CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y |
||||||
|
CONFIG_ESP32_WIFI_TX_BA_WIN=6 |
||||||
|
CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y |
||||||
|
CONFIG_ESP32_WIFI_RX_BA_WIN=6 |
||||||
|
CONFIG_ESP32_WIFI_NVS_ENABLED=y |
||||||
|
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y |
||||||
|
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1= |
||||||
|
CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 |
||||||
|
|
||||||
|
# |
||||||
|
# PHY |
||||||
|
# |
||||||
|
CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y |
||||||
|
CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION= |
||||||
|
CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 |
||||||
|
CONFIG_ESP32_PHY_MAX_TX_POWER=20 |
||||||
|
|
||||||
|
# |
||||||
|
# Power Management |
||||||
|
# |
||||||
|
CONFIG_PM_ENABLE= |
||||||
|
|
||||||
|
# |
||||||
|
# Log output |
||||||
|
# |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_NONE= |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_ERROR= |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_WARN= |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_INFO= |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_DEBUG=y |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL_VERBOSE= |
||||||
|
CONFIG_LOG_DEFAULT_LEVEL=4 |
||||||
|
CONFIG_LOG_COLORS=y |
||||||
|
|
||||||
|
# |
||||||
|
# PThreads |
||||||
|
# |
||||||
|
CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 |
||||||
|
CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 |
||||||
|
|
||||||
|
# |
||||||
|
# ADC-Calibration |
||||||
|
# |
||||||
|
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y |
||||||
|
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y |
||||||
|
CONFIG_ADC_CAL_LUT_ENABLE=y |
||||||
|
|
||||||
|
# |
||||||
|
# ESP HTTP client |
||||||
|
# |
||||||
|
CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS=y |
||||||
|
|
||||||
|
# |
||||||
|
# FAT Filesystem support |
||||||
|
# |
||||||
|
CONFIG_FATFS_CODEPAGE_DYNAMIC= |
||||||
|
CONFIG_FATFS_CODEPAGE_437=y |
||||||
|
CONFIG_FATFS_CODEPAGE_720= |
||||||
|
CONFIG_FATFS_CODEPAGE_737= |
||||||
|
CONFIG_FATFS_CODEPAGE_771= |
||||||
|
CONFIG_FATFS_CODEPAGE_775= |
||||||
|
CONFIG_FATFS_CODEPAGE_850= |
||||||
|
CONFIG_FATFS_CODEPAGE_852= |
||||||
|
CONFIG_FATFS_CODEPAGE_855= |
||||||
|
CONFIG_FATFS_CODEPAGE_857= |
||||||
|
CONFIG_FATFS_CODEPAGE_860= |
||||||
|
CONFIG_FATFS_CODEPAGE_861= |
||||||
|
CONFIG_FATFS_CODEPAGE_862= |
||||||
|
CONFIG_FATFS_CODEPAGE_863= |
||||||
|
CONFIG_FATFS_CODEPAGE_864= |
||||||
|
CONFIG_FATFS_CODEPAGE_865= |
||||||
|
CONFIG_FATFS_CODEPAGE_866= |
||||||
|
CONFIG_FATFS_CODEPAGE_869= |
||||||
|
CONFIG_FATFS_CODEPAGE_932= |
||||||
|
CONFIG_FATFS_CODEPAGE_936= |
||||||
|
CONFIG_FATFS_CODEPAGE_949= |
||||||
|
CONFIG_FATFS_CODEPAGE_950= |
||||||
|
CONFIG_FATFS_CODEPAGE=437 |
||||||
|
CONFIG_FATFS_LFN_NONE=y |
||||||
|
CONFIG_FATFS_LFN_HEAP= |
||||||
|
CONFIG_FATFS_LFN_STACK= |
||||||
|
CONFIG_FATFS_FS_LOCK=0 |
||||||
|
CONFIG_FATFS_TIMEOUT_MS=10000 |
||||||
|
CONFIG_FATFS_PER_FILE_CACHE=y |
||||||
|
|
||||||
|
# |
||||||
|
# Wear Levelling |
||||||
|
# |
||||||
|
CONFIG_WL_SECTOR_SIZE_512= |
||||||
|
CONFIG_WL_SECTOR_SIZE_4096=y |
||||||
|
CONFIG_WL_SECTOR_SIZE=4096 |
||||||
|
|
||||||
|
# |
||||||
|
# FreeRTOS |
||||||
|
# |
||||||
|
CONFIG_FREERTOS_UNICORE= |
||||||
|
CONFIG_FREERTOS_CORETIMER_0=y |
||||||
|
CONFIG_FREERTOS_CORETIMER_1= |
||||||
|
CONFIG_FREERTOS_HZ=100 |
||||||
|
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y |
||||||
|
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE= |
||||||
|
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL= |
||||||
|
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y |
||||||
|
CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK= |
||||||
|
CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y |
||||||
|
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1 |
||||||
|
CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y |
||||||
|
CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE= |
||||||
|
CONFIG_FREERTOS_ASSERT_DISABLE= |
||||||
|
CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536 |
||||||
|
CONFIG_FREERTOS_ISR_STACKSIZE=1536 |
||||||
|
CONFIG_FREERTOS_LEGACY_HOOKS= |
||||||
|
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 |
||||||
|
CONFIG_SUPPORT_STATIC_ALLOCATION= |
||||||
|
CONFIG_TIMER_TASK_PRIORITY=1 |
||||||
|
CONFIG_TIMER_TASK_STACK_DEPTH=2048 |
||||||
|
CONFIG_TIMER_QUEUE_LENGTH=10 |
||||||
|
CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0 |
||||||
|
CONFIG_FREERTOS_USE_TRACE_FACILITY= |
||||||
|
CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS= |
||||||
|
CONFIG_FREERTOS_DEBUG_INTERNALS= |
||||||
|
|
||||||
|
# |
||||||
|
# Heap memory debugging |
||||||
|
# |
||||||
|
CONFIG_HEAP_POISONING_DISABLED= |
||||||
|
CONFIG_HEAP_POISONING_LIGHT= |
||||||
|
CONFIG_HEAP_POISONING_COMPREHENSIVE=y |
||||||
|
CONFIG_HEAP_TRACING= |
||||||
|
CONFIG_HEAP_TASK_TRACKING= |
||||||
|
|
||||||
|
# |
||||||
|
# libsodium |
||||||
|
# |
||||||
|
CONFIG_LIBSODIUM_USE_MBEDTLS_SHA=y |
||||||
|
|
||||||
|
# |
||||||
|
# OpenSSL |
||||||
|
# |
||||||
|
CONFIG_OPENSSL_DEBUG= |
||||||
|
CONFIG_OPENSSL_ASSERT_DO_NOTHING=y |
||||||
|
CONFIG_OPENSSL_ASSERT_EXIT= |
||||||
|
|
||||||
|
# |
||||||
|
# SPIFFS Configuration |
||||||
|
# |
||||||
|
CONFIG_SPIFFS_MAX_PARTITIONS=3 |
||||||
|
|
||||||
|
# |
||||||
|
# SPIFFS Cache Configuration |
||||||
|
# |
||||||
|
CONFIG_SPIFFS_CACHE=y |
||||||
|
CONFIG_SPIFFS_CACHE_WR=y |
||||||
|
CONFIG_SPIFFS_CACHE_STATS= |
||||||
|
CONFIG_SPIFFS_PAGE_CHECK=y |
||||||
|
CONFIG_SPIFFS_GC_MAX_RUNS=10 |
||||||
|
CONFIG_SPIFFS_GC_STATS= |
||||||
|
CONFIG_SPIFFS_PAGE_SIZE=256 |
||||||
|
CONFIG_SPIFFS_OBJ_NAME_LEN=32 |
||||||
|
CONFIG_SPIFFS_USE_MAGIC=y |
||||||
|
CONFIG_SPIFFS_USE_MAGIC_LENGTH=y |
||||||
|
CONFIG_SPIFFS_META_LENGTH=4 |
||||||
|
CONFIG_SPIFFS_USE_MTIME=y |
||||||
|
|
||||||
|
# |
||||||
|
# Debug Configuration |
||||||
|
# |
||||||
|
CONFIG_SPIFFS_DBG= |
||||||
|
CONFIG_SPIFFS_API_DBG= |
||||||
|
CONFIG_SPIFFS_GC_DBG= |
||||||
|
CONFIG_SPIFFS_CACHE_DBG= |
||||||
|
CONFIG_SPIFFS_CHECK_DBG= |
||||||
|
CONFIG_SPIFFS_TEST_VISUALISATION= |
@ -0,0 +1,12 @@ |
|||||||
|
REVISION: 1 |
||||||
|
angle_pid: |
||||||
|
kp: 0.04 |
||||||
|
ki: 0.00 #0001 |
||||||
|
kd: 0.4 |
||||||
|
max_output: 0.4 |
||||||
|
max_i_error: 15.0 |
||||||
|
|
||||||
|
min_target_dist: 1.0 |
||||||
|
min_flip_pitch: 90.0 |
||||||
|
drive_power: 0.3 |
||||||
|
mag_declination: 11.5 |
@ -0,0 +1,43 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
|
||||||
|
import config_pb2 |
||||||
|
import yaml |
||||||
|
|
||||||
|
|
||||||
|
def dict2pb(d, pb): |
||||||
|
for key in d: |
||||||
|
val = d[key] |
||||||
|
if isinstance(val, dict): |
||||||
|
dict2pb(val, getattr(pb, key)) |
||||||
|
else: |
||||||
|
setattr(pb, key, val) |
||||||
|
|
||||||
|
|
||||||
|
def main(): |
||||||
|
with open('./tools/config.yml', 'r') as configfile: |
||||||
|
config = yaml.load(configfile) |
||||||
|
|
||||||
|
if 'REVISION' in config: |
||||||
|
config_rev = config['REVISION'] |
||||||
|
del config['REVISION'] |
||||||
|
else: |
||||||
|
config_rev = 1 |
||||||
|
|
||||||
|
confpb = config_pb2.Config() |
||||||
|
dict2pb(config, confpb) |
||||||
|
|
||||||
|
pbdata = confpb.SerializeToString() |
||||||
|
|
||||||
|
pbdataarry = ','.join([str(int(b)) for b in pbdata]) |
||||||
|
|
||||||
|
cfile = """#include <stdint.h> |
||||||
|
|
||||||
|
uint8_t CONFIG_DATA[] = {%s}; |
||||||
|
size_t CONFIG_DATA_LEN = %s; |
||||||
|
int CONFIG_REV = %s;""" % (pbdataarry, len(pbdata), int(config_rev)) |
||||||
|
|
||||||
|
print(cfile) |
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
main() |
@ -0,0 +1,167 @@ |
|||||||
|
# -*- coding: utf-8 -*- |
||||||
|
# Generated by the protocol buffer compiler. DO NOT EDIT! |
||||||
|
# source: config.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 |
||||||
|
# @@protoc_insertion_point(imports) |
||||||
|
|
||||||
|
_sym_db = _symbol_database.Default() |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
DESCRIPTOR = _descriptor.FileDescriptor( |
||||||
|
name='config.proto', |
||||||
|
package='ugv.config', |
||||||
|
syntax='proto3', |
||||||
|
serialized_options=_b('H\003'), |
||||||
|
serialized_pb=_b('\n\x0c\x63onfig.proto\x12\nugv.config\"X\n\tPidParams\x12\n\n\x02kp\x18\x01 \x01(\x02\x12\n\n\x02ki\x18\x02 \x01(\x02\x12\n\n\x02kd\x18\x03 \x01(\x02\x12\x12\n\nmax_output\x18\x04 \x01(\x02\x12\x13\n\x0bmax_i_error\x18\x05 \x01(\x02\"\x91\x01\n\x06\x43onfig\x12\x17\n\x0fmin_target_dist\x18\x01 \x01(\x02\x12\x13\n\x0b\x64rive_power\x18\x02 \x01(\x02\x12(\n\tangle_pid\x18\x03 \x01(\x0b\x32\x15.ugv.config.PidParams\x12\x16\n\x0emin_flip_pitch\x18\x04 \x01(\x02\x12\x17\n\x0fmag_declination\x18\x05 \x01(\x02\x42\x02H\x03\x62\x06proto3') |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
_PIDPARAMS = _descriptor.Descriptor( |
||||||
|
name='PidParams', |
||||||
|
full_name='ugv.config.PidParams', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='kp', full_name='ugv.config.PidParams.kp', index=0, |
||||||
|
number=1, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='ki', full_name='ugv.config.PidParams.ki', index=1, |
||||||
|
number=2, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='kd', full_name='ugv.config.PidParams.kd', index=2, |
||||||
|
number=3, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='max_output', full_name='ugv.config.PidParams.max_output', index=3, |
||||||
|
number=4, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='max_i_error', full_name='ugv.config.PidParams.max_i_error', index=4, |
||||||
|
number=5, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=28, |
||||||
|
serialized_end=116, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_CONFIG = _descriptor.Descriptor( |
||||||
|
name='Config', |
||||||
|
full_name='ugv.config.Config', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='min_target_dist', full_name='ugv.config.Config.min_target_dist', index=0, |
||||||
|
number=1, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='drive_power', full_name='ugv.config.Config.drive_power', index=1, |
||||||
|
number=2, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='angle_pid', full_name='ugv.config.Config.angle_pid', index=2, |
||||||
|
number=3, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='min_flip_pitch', full_name='ugv.config.Config.min_flip_pitch', index=3, |
||||||
|
number=4, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='mag_declination', full_name='ugv.config.Config.mag_declination', index=4, |
||||||
|
number=5, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=119, |
||||||
|
serialized_end=264, |
||||||
|
) |
||||||
|
|
||||||
|
_CONFIG.fields_by_name['angle_pid'].message_type = _PIDPARAMS |
||||||
|
DESCRIPTOR.message_types_by_name['PidParams'] = _PIDPARAMS |
||||||
|
DESCRIPTOR.message_types_by_name['Config'] = _CONFIG |
||||||
|
_sym_db.RegisterFileDescriptor(DESCRIPTOR) |
||||||
|
|
||||||
|
PidParams = _reflection.GeneratedProtocolMessageType('PidParams', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _PIDPARAMS, |
||||||
|
__module__ = 'config_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.config.PidParams) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(PidParams) |
||||||
|
|
||||||
|
Config = _reflection.GeneratedProtocolMessageType('Config', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _CONFIG, |
||||||
|
__module__ = 'config_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.config.Config) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(Config) |
||||||
|
|
||||||
|
|
||||||
|
DESCRIPTOR._options = None |
||||||
|
# @@protoc_insertion_point(module_scope) |
@ -0,0 +1,167 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
|
||||||
|
import serial |
||||||
|
import struct |
||||||
|
|
||||||
|
PARITY_NONE = 0 |
||||||
|
PARITY_ODD = 1 |
||||||
|
PARITY_EVEN = 2 |
||||||
|
|
||||||
|
BAUD_TABLE = { |
||||||
|
0: 1200, |
||||||
|
1: 2400, |
||||||
|
2: 4800, |
||||||
|
3: 9600, |
||||||
|
4: 19200, |
||||||
|
5: 38400, |
||||||
|
6: 57600, |
||||||
|
7: 115200, |
||||||
|
} |
||||||
|
|
||||||
|
AIR_DATA_RATE_TABLE = { |
||||||
|
0: 300, |
||||||
|
1: 1200, |
||||||
|
2: 2400, |
||||||
|
3: 4800, |
||||||
|
4: 9600, |
||||||
|
5: 19200, |
||||||
|
6: 19200, |
||||||
|
7: 19200, |
||||||
|
} |
||||||
|
|
||||||
|
TX_MODE_TRANSPARENT = 0 |
||||||
|
TX_MODE_FIXED = 1 |
||||||
|
|
||||||
|
IO_MODE_OPEN_COLLECTOR = 0 |
||||||
|
IO_MODE_PUSH_PULL = 1 |
||||||
|
|
||||||
|
TX_POWER_TABLE = { |
||||||
|
0: 30, |
||||||
|
1: 27, |
||||||
|
2: 24, |
||||||
|
3: 21, |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
def least_gte(value, dic): |
||||||
|
items = sorted(dic.items(), key=lambda item: item[1]) |
||||||
|
last_k = None |
||||||
|
for k, v in items: |
||||||
|
last_k = k |
||||||
|
if v >= value: |
||||||
|
break |
||||||
|
return last_k |
||||||
|
|
||||||
|
|
||||||
|
class E32_Params: |
||||||
|
save: bool |
||||||
|
address: int |
||||||
|
parity: int |
||||||
|
baud: int |
||||||
|
air_data_rate: int |
||||||
|
channel: int |
||||||
|
tx_mode: int |
||||||
|
io_mode: int |
||||||
|
wake_up_time: int |
||||||
|
fec_enabled: bool |
||||||
|
tx_power: int |
||||||
|
|
||||||
|
@staticmethod |
||||||
|
def default(): |
||||||
|
p = E32_Params() |
||||||
|
p.save = True |
||||||
|
p.address = 0 |
||||||
|
p.parity = PARITY_NONE |
||||||
|
p.baud = 9600 |
||||||
|
p.air_data_rate = 2400 |
||||||
|
p.channel = 0x17 |
||||||
|
p.tx_mode = TX_MODE_TRANSPARENT |
||||||
|
p.io_mode = IO_MODE_PUSH_PULL |
||||||
|
p.wake_up_time = 250 |
||||||
|
p.fec_enabled = True |
||||||
|
p.tx_power = 30 |
||||||
|
return p |
||||||
|
|
||||||
|
@staticmethod |
||||||
|
def unpack(data): |
||||||
|
p = E32_Params() |
||||||
|
datab = bytes(data) |
||||||
|
if len(datab) != 6: |
||||||
|
raise Exception('invalid E32_Params data length') |
||||||
|
if datab[0] == 0xC0: |
||||||
|
p.save = True |
||||||
|
elif datab[0] == 0xC2: |
||||||
|
p.save = False |
||||||
|
else: |
||||||
|
raise Exception('invalid E32_Params data header') |
||||||
|
p.address = (datab[1] << 8) | datab[2] |
||||||
|
p.parity = (datab[3] >> 6) & 0b11 |
||||||
|
p.baud = BAUD_TABLE[(datab[3] >> 3) & 0b111] |
||||||
|
p.air_data_rate = AIR_DATA_RATE_TABLE[datab[3] & 0b111] |
||||||
|
p.channel = datab[4] |
||||||
|
p.tx_mode = (datab[5] >> 7) & 1 |
||||||
|
p.io_mode = (datab[5] >> 6) & 1 |
||||||
|
p.wake_up_time = 250 * (((datab[5] >> 3) & 0b111) + 1) |
||||||
|
p.fec_enabled = (datab[5] & (1 << 2)) != 0 |
||||||
|
p.tx_power = TX_POWER_TABLE[datab[5] & 0b11] |
||||||
|
return p |
||||||
|
|
||||||
|
def pack(self): |
||||||
|
p = self |
||||||
|
datab = bytearray(range(6)) |
||||||
|
if p.save: |
||||||
|
datab[0] = 0xC0 |
||||||
|
else: |
||||||
|
datab[0] = 0xC2 |
||||||
|
datab[1] = (p.address >> 8) & 0xFF |
||||||
|
datab[2] = (p.address) & 0xFF |
||||||
|
datab[3] = 0 |
||||||
|
datab[3] |= p.parity << 6 |
||||||
|
datab[3] |= (least_gte(p.baud, BAUD_TABLE) << 3) |
||||||
|
datab[3] |= (least_gte(p.air_data_rate, AIR_DATA_RATE_TABLE)) |
||||||
|
datab[4] = p.channel |
||||||
|
datab[5] = 0 |
||||||
|
datab[5] |= p.tx_mode << 7 |
||||||
|
datab[5] |= p.io_mode << 6 |
||||||
|
datab[5] |= (int((p.wake_up_time / 250) - 1) & 0b111) << 3 |
||||||
|
datab[5] |= p.fec_enabled << 2 |
||||||
|
datab[5] |= least_gte(p.tx_power, TX_POWER_TABLE) |
||||||
|
return datab |
||||||
|
|
||||||
|
|
||||||
|
class E32: |
||||||
|
ser: serial.Serial |
||||||
|
|
||||||
|
def __init__(self, serial_port: serial.Serial): |
||||||
|
self.ser = serial_port |
||||||
|
|
||||||
|
def close(self): |
||||||
|
self.ser.close() |
||||||
|
|
||||||
|
def read_version(self): |
||||||
|
# self.ser.flush() |
||||||
|
self.ser.write(b'\xC3\xC3\xC3') |
||||||
|
version = self.ser.read(size=4) |
||||||
|
print("version: ", version) |
||||||
|
return version |
||||||
|
|
||||||
|
def reset(self): |
||||||
|
# self.ser.flush() |
||||||
|
print("writing: ", b'\xC4\xC4\xC4') |
||||||
|
self.ser.write(b'0xC40xC40xC4') |
||||||
|
|
||||||
|
def read_params(self): |
||||||
|
# self.ser.flush() |
||||||
|
self.ser.write(b'\xC1\xC1\xC1') |
||||||
|
param_bytes = self.ser.read(size=6) |
||||||
|
print("param_bytes: ", param_bytes) |
||||||
|
return E32_Params.unpack(param_bytes) |
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
p = E32_Params.default() |
||||||
|
print("params: ", p.__dict__) |
||||||
|
data = p.pack() |
||||||
|
print("packed data: ", ', '.join(format(x, '02x') for x in data)) |
||||||
|
p2 = E32_Params.unpack(data) |
||||||
|
print("unpacked params: ", p2.__dict__) |
@ -0,0 +1,562 @@ |
|||||||
|
# -*- coding: utf-8 -*- |
||||||
|
# Generated by the protocol buffer compiler. DO NOT EDIT! |
||||||
|
# source: messages.proto |
||||||
|
|
||||||
|
import sys |
||||||
|
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1')) |
||||||
|
from google.protobuf.internal import enum_type_wrapper |
||||||
|
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 |
||||||
|
# @@protoc_insertion_point(imports) |
||||||
|
|
||||||
|
_sym_db = _symbol_database.Default() |
||||||
|
|
||||||
|
|
||||||
|
import config_pb2 as config__pb2 |
||||||
|
|
||||||
|
from config_pb2 import * |
||||||
|
|
||||||
|
DESCRIPTOR = _descriptor.FileDescriptor( |
||||||
|
name='messages.proto', |
||||||
|
package='ugv.messages', |
||||||
|
syntax='proto3', |
||||||
|
serialized_options=_b('H\003'), |
||||||
|
serialized_pb=_b('\n\x0emessages.proto\x12\x0cugv.messages\x1a\x0c\x63onfig.proto\"5\n\x0eTargetLocation\x12\x10\n\x08latitude\x18\x01 \x01(\x02\x12\x11\n\tlongitude\x18\x02 \x01(\x02\"V\n\x08Location\x12\x13\n\x0b\x66ix_quality\x18\x01 \x01(\r\x12\x10\n\x08latitude\x18\x02 \x01(\x02\x12\x11\n\tlongitude\x18\x03 \x01(\x02\x12\x10\n\x08\x61ltitude\x18\x04 \x01(\x02\"\xac\x01\n\nUGV_Status\x12&\n\x05state\x18\x01 \x01(\x0e\x32\x17.ugv.messages.UGV_State\x12(\n\x08location\x18\x02 \x01(\x0b\x32\x16.ugv.messages.Location\x12\x11\n\tyaw_angle\x18\x03 \x01(\x02\x12\x13\n\x0bpitch_angle\x18\x04 \x01(\x02\x12\x12\n\nroll_angle\x18\x05 \x01(\x02\x12\x10\n\x08is_still\x18\x06 \x01(\x08\"_\n\x0bUGV_Message\x12*\n\x06status\x18\x01 \x01(\x0b\x32\x18.ugv.messages.UGV_StatusH\x00\x12\x15\n\x0b\x63ommand_ack\x18\x02 \x01(\rH\x00\x42\r\n\x0bugv_message\"2\n\x10\x44riveHeadingData\x12\x0f\n\x07heading\x18\x01 \x01(\x02\x12\r\n\x05power\x18\x02 \x01(\x02\"\xea\x01\n\rGroundCommand\x12\n\n\x02id\x18\x01 \x01(\r\x12-\n\x04type\x18\x02 \x01(\x0e\x32\x1f.ugv.messages.GroundCommandType\x12\x37\n\rdrive_heading\x18\x03 \x01(\x0b\x32\x1e.ugv.messages.DriveHeadingDataH\x00\x12\x37\n\x0ftarget_location\x18\x04 \x01(\x0b\x32\x1c.ugv.messages.TargetLocationH\x00\x12$\n\x06\x63onfig\x18\x05 \x01(\x0b\x32\x12.ugv.config.ConfigH\x00\x42\x06\n\x04\x64\x61ta\"Q\n\rGroundMessage\x12.\n\x07\x63ommand\x18\x01 \x01(\x0b\x32\x1b.ugv.messages.GroundCommandH\x00\x42\x10\n\x0eground_message*\xa6\x01\n\tUGV_State\x12\x0e\n\nSTATE_IDLE\x10\x00\x12\x12\n\x0eSTATE_AQUIRING\x10\x01\x12\x11\n\rSTATE_DRIVING\x10\x02\x12\x12\n\x0eSTATE_FINISHED\x10\x03\x12\x0e\n\nSTATE_TEST\x10\x04\x12\x12\n\x0eSTATE_FLIPPING\x10\x05\x12\x11\n\rSTATE_TURNING\x10\x06\x12\x17\n\x13STATE_DRIVE_HEADING\x10\x07*\xac\x01\n\x11GroundCommandType\x12\x0f\n\x0b\x43MD_DISABLE\x10\x00\x12\x17\n\x13\x43MD_DRIVE_TO_TARGET\x10\x01\x12\x0c\n\x08\x43MD_TEST\x10\x02\x12\x15\n\x11\x43MD_DRIVE_HEADING\x10\x03\x12\x12\n\x0e\x43MD_SET_TARGET\x10\x04\x12\x12\n\x0e\x43MD_SET_CONFIG\x10\x05\x12\x12\n\x0e\x43MD_GET_STATUS\x10\x06\x12\x0c\n\x08\x43MD_PING\x10\x07\x42\x02H\x03P\x00\x62\x06proto3') |
||||||
|
, |
||||||
|
dependencies=[config__pb2.DESCRIPTOR,], |
||||||
|
public_dependencies=[config__pb2.DESCRIPTOR,]) |
||||||
|
|
||||||
|
_UGV_STATE = _descriptor.EnumDescriptor( |
||||||
|
name='UGV_State', |
||||||
|
full_name='ugv.messages.UGV_State', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
values=[ |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_IDLE', index=0, number=0, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_AQUIRING', index=1, number=1, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_DRIVING', index=2, number=2, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_FINISHED', index=3, number=3, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_TEST', index=4, number=4, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_FLIPPING', index=5, number=5, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_TURNING', index=6, number=6, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='STATE_DRIVE_HEADING', index=7, number=7, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
], |
||||||
|
containing_type=None, |
||||||
|
serialized_options=None, |
||||||
|
serialized_start=834, |
||||||
|
serialized_end=1000, |
||||||
|
) |
||||||
|
_sym_db.RegisterEnumDescriptor(_UGV_STATE) |
||||||
|
|
||||||
|
UGV_State = enum_type_wrapper.EnumTypeWrapper(_UGV_STATE) |
||||||
|
_GROUNDCOMMANDTYPE = _descriptor.EnumDescriptor( |
||||||
|
name='GroundCommandType', |
||||||
|
full_name='ugv.messages.GroundCommandType', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
values=[ |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_DISABLE', index=0, number=0, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_DRIVE_TO_TARGET', index=1, number=1, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_TEST', index=2, number=2, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_DRIVE_HEADING', index=3, number=3, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_SET_TARGET', index=4, number=4, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_SET_CONFIG', index=5, number=5, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_GET_STATUS', index=6, number=6, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
_descriptor.EnumValueDescriptor( |
||||||
|
name='CMD_PING', index=7, number=7, |
||||||
|
serialized_options=None, |
||||||
|
type=None), |
||||||
|
], |
||||||
|
containing_type=None, |
||||||
|
serialized_options=None, |
||||||
|
serialized_start=1003, |
||||||
|
serialized_end=1175, |
||||||
|
) |
||||||
|
_sym_db.RegisterEnumDescriptor(_GROUNDCOMMANDTYPE) |
||||||
|
|
||||||
|
GroundCommandType = enum_type_wrapper.EnumTypeWrapper(_GROUNDCOMMANDTYPE) |
||||||
|
STATE_IDLE = 0 |
||||||
|
STATE_AQUIRING = 1 |
||||||
|
STATE_DRIVING = 2 |
||||||
|
STATE_FINISHED = 3 |
||||||
|
STATE_TEST = 4 |
||||||
|
STATE_FLIPPING = 5 |
||||||
|
STATE_TURNING = 6 |
||||||
|
STATE_DRIVE_HEADING = 7 |
||||||
|
CMD_DISABLE = 0 |
||||||
|
CMD_DRIVE_TO_TARGET = 1 |
||||||
|
CMD_TEST = 2 |
||||||
|
CMD_DRIVE_HEADING = 3 |
||||||
|
CMD_SET_TARGET = 4 |
||||||
|
CMD_SET_CONFIG = 5 |
||||||
|
CMD_GET_STATUS = 6 |
||||||
|
CMD_PING = 7 |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
_TARGETLOCATION = _descriptor.Descriptor( |
||||||
|
name='TargetLocation', |
||||||
|
full_name='ugv.messages.TargetLocation', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='latitude', full_name='ugv.messages.TargetLocation.latitude', index=0, |
||||||
|
number=1, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='longitude', full_name='ugv.messages.TargetLocation.longitude', index=1, |
||||||
|
number=2, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=46, |
||||||
|
serialized_end=99, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_LOCATION = _descriptor.Descriptor( |
||||||
|
name='Location', |
||||||
|
full_name='ugv.messages.Location', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='fix_quality', full_name='ugv.messages.Location.fix_quality', index=0, |
||||||
|
number=1, type=13, cpp_type=3, label=1, |
||||||
|
has_default_value=False, default_value=0, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='latitude', full_name='ugv.messages.Location.latitude', index=1, |
||||||
|
number=2, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='longitude', full_name='ugv.messages.Location.longitude', index=2, |
||||||
|
number=3, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='altitude', full_name='ugv.messages.Location.altitude', index=3, |
||||||
|
number=4, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=101, |
||||||
|
serialized_end=187, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_UGV_STATUS = _descriptor.Descriptor( |
||||||
|
name='UGV_Status', |
||||||
|
full_name='ugv.messages.UGV_Status', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='state', full_name='ugv.messages.UGV_Status.state', index=0, |
||||||
|
number=1, type=14, cpp_type=8, label=1, |
||||||
|
has_default_value=False, default_value=0, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='location', full_name='ugv.messages.UGV_Status.location', index=1, |
||||||
|
number=2, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='yaw_angle', full_name='ugv.messages.UGV_Status.yaw_angle', index=2, |
||||||
|
number=3, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='pitch_angle', full_name='ugv.messages.UGV_Status.pitch_angle', index=3, |
||||||
|
number=4, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='roll_angle', full_name='ugv.messages.UGV_Status.roll_angle', index=4, |
||||||
|
number=5, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='is_still', full_name='ugv.messages.UGV_Status.is_still', index=5, |
||||||
|
number=6, type=8, cpp_type=7, label=1, |
||||||
|
has_default_value=False, default_value=False, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=190, |
||||||
|
serialized_end=362, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_UGV_MESSAGE = _descriptor.Descriptor( |
||||||
|
name='UGV_Message', |
||||||
|
full_name='ugv.messages.UGV_Message', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='status', full_name='ugv.messages.UGV_Message.status', index=0, |
||||||
|
number=1, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='command_ack', full_name='ugv.messages.UGV_Message.command_ack', index=1, |
||||||
|
number=2, type=13, cpp_type=3, label=1, |
||||||
|
has_default_value=False, default_value=0, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
_descriptor.OneofDescriptor( |
||||||
|
name='ugv_message', full_name='ugv.messages.UGV_Message.ugv_message', |
||||||
|
index=0, containing_type=None, fields=[]), |
||||||
|
], |
||||||
|
serialized_start=364, |
||||||
|
serialized_end=459, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_DRIVEHEADINGDATA = _descriptor.Descriptor( |
||||||
|
name='DriveHeadingData', |
||||||
|
full_name='ugv.messages.DriveHeadingData', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='heading', full_name='ugv.messages.DriveHeadingData.heading', index=0, |
||||||
|
number=1, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='power', full_name='ugv.messages.DriveHeadingData.power', index=1, |
||||||
|
number=2, type=2, cpp_type=6, label=1, |
||||||
|
has_default_value=False, default_value=float(0), |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
], |
||||||
|
serialized_start=461, |
||||||
|
serialized_end=511, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_GROUNDCOMMAND = _descriptor.Descriptor( |
||||||
|
name='GroundCommand', |
||||||
|
full_name='ugv.messages.GroundCommand', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='id', full_name='ugv.messages.GroundCommand.id', index=0, |
||||||
|
number=1, type=13, cpp_type=3, label=1, |
||||||
|
has_default_value=False, default_value=0, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='type', full_name='ugv.messages.GroundCommand.type', index=1, |
||||||
|
number=2, type=14, cpp_type=8, label=1, |
||||||
|
has_default_value=False, default_value=0, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='drive_heading', full_name='ugv.messages.GroundCommand.drive_heading', index=2, |
||||||
|
number=3, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='target_location', full_name='ugv.messages.GroundCommand.target_location', index=3, |
||||||
|
number=4, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='config', full_name='ugv.messages.GroundCommand.config', index=4, |
||||||
|
number=5, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
_descriptor.OneofDescriptor( |
||||||
|
name='data', full_name='ugv.messages.GroundCommand.data', |
||||||
|
index=0, containing_type=None, fields=[]), |
||||||
|
], |
||||||
|
serialized_start=514, |
||||||
|
serialized_end=748, |
||||||
|
) |
||||||
|
|
||||||
|
|
||||||
|
_GROUNDMESSAGE = _descriptor.Descriptor( |
||||||
|
name='GroundMessage', |
||||||
|
full_name='ugv.messages.GroundMessage', |
||||||
|
filename=None, |
||||||
|
file=DESCRIPTOR, |
||||||
|
containing_type=None, |
||||||
|
fields=[ |
||||||
|
_descriptor.FieldDescriptor( |
||||||
|
name='command', full_name='ugv.messages.GroundMessage.command', index=0, |
||||||
|
number=1, type=11, cpp_type=10, label=1, |
||||||
|
has_default_value=False, default_value=None, |
||||||
|
message_type=None, enum_type=None, containing_type=None, |
||||||
|
is_extension=False, extension_scope=None, |
||||||
|
serialized_options=None, file=DESCRIPTOR), |
||||||
|
], |
||||||
|
extensions=[ |
||||||
|
], |
||||||
|
nested_types=[], |
||||||
|
enum_types=[ |
||||||
|
], |
||||||
|
serialized_options=None, |
||||||
|
is_extendable=False, |
||||||
|
syntax='proto3', |
||||||
|
extension_ranges=[], |
||||||
|
oneofs=[ |
||||||
|
_descriptor.OneofDescriptor( |
||||||
|
name='ground_message', full_name='ugv.messages.GroundMessage.ground_message', |
||||||
|
index=0, containing_type=None, fields=[]), |
||||||
|
], |
||||||
|
serialized_start=750, |
||||||
|
serialized_end=831, |
||||||
|
) |
||||||
|
|
||||||
|
_UGV_STATUS.fields_by_name['state'].enum_type = _UGV_STATE |
||||||
|
_UGV_STATUS.fields_by_name['location'].message_type = _LOCATION |
||||||
|
_UGV_MESSAGE.fields_by_name['status'].message_type = _UGV_STATUS |
||||||
|
_UGV_MESSAGE.oneofs_by_name['ugv_message'].fields.append( |
||||||
|
_UGV_MESSAGE.fields_by_name['status']) |
||||||
|
_UGV_MESSAGE.fields_by_name['status'].containing_oneof = _UGV_MESSAGE.oneofs_by_name['ugv_message'] |
||||||
|
_UGV_MESSAGE.oneofs_by_name['ugv_message'].fields.append( |
||||||
|
_UGV_MESSAGE.fields_by_name['command_ack']) |
||||||
|
_UGV_MESSAGE.fields_by_name['command_ack'].containing_oneof = _UGV_MESSAGE.oneofs_by_name['ugv_message'] |
||||||
|
_GROUNDCOMMAND.fields_by_name['type'].enum_type = _GROUNDCOMMANDTYPE |
||||||
|
_GROUNDCOMMAND.fields_by_name['drive_heading'].message_type = _DRIVEHEADINGDATA |
||||||
|
_GROUNDCOMMAND.fields_by_name['target_location'].message_type = _TARGETLOCATION |
||||||
|
_GROUNDCOMMAND.fields_by_name['config'].message_type = config__pb2._CONFIG |
||||||
|
_GROUNDCOMMAND.oneofs_by_name['data'].fields.append( |
||||||
|
_GROUNDCOMMAND.fields_by_name['drive_heading']) |
||||||
|
_GROUNDCOMMAND.fields_by_name['drive_heading'].containing_oneof = _GROUNDCOMMAND.oneofs_by_name['data'] |
||||||
|
_GROUNDCOMMAND.oneofs_by_name['data'].fields.append( |
||||||
|
_GROUNDCOMMAND.fields_by_name['target_location']) |
||||||
|
_GROUNDCOMMAND.fields_by_name['target_location'].containing_oneof = _GROUNDCOMMAND.oneofs_by_name['data'] |
||||||
|
_GROUNDCOMMAND.oneofs_by_name['data'].fields.append( |
||||||
|
_GROUNDCOMMAND.fields_by_name['config']) |
||||||
|
_GROUNDCOMMAND.fields_by_name['config'].containing_oneof = _GROUNDCOMMAND.oneofs_by_name['data'] |
||||||
|
_GROUNDMESSAGE.fields_by_name['command'].message_type = _GROUNDCOMMAND |
||||||
|
_GROUNDMESSAGE.oneofs_by_name['ground_message'].fields.append( |
||||||
|
_GROUNDMESSAGE.fields_by_name['command']) |
||||||
|
_GROUNDMESSAGE.fields_by_name['command'].containing_oneof = _GROUNDMESSAGE.oneofs_by_name['ground_message'] |
||||||
|
DESCRIPTOR.message_types_by_name['TargetLocation'] = _TARGETLOCATION |
||||||
|
DESCRIPTOR.message_types_by_name['Location'] = _LOCATION |
||||||
|
DESCRIPTOR.message_types_by_name['UGV_Status'] = _UGV_STATUS |
||||||
|
DESCRIPTOR.message_types_by_name['UGV_Message'] = _UGV_MESSAGE |
||||||
|
DESCRIPTOR.message_types_by_name['DriveHeadingData'] = _DRIVEHEADINGDATA |
||||||
|
DESCRIPTOR.message_types_by_name['GroundCommand'] = _GROUNDCOMMAND |
||||||
|
DESCRIPTOR.message_types_by_name['GroundMessage'] = _GROUNDMESSAGE |
||||||
|
DESCRIPTOR.enum_types_by_name['UGV_State'] = _UGV_STATE |
||||||
|
DESCRIPTOR.enum_types_by_name['GroundCommandType'] = _GROUNDCOMMANDTYPE |
||||||
|
_sym_db.RegisterFileDescriptor(DESCRIPTOR) |
||||||
|
|
||||||
|
TargetLocation = _reflection.GeneratedProtocolMessageType('TargetLocation', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _TARGETLOCATION, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.TargetLocation) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(TargetLocation) |
||||||
|
|
||||||
|
Location = _reflection.GeneratedProtocolMessageType('Location', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _LOCATION, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.Location) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(Location) |
||||||
|
|
||||||
|
UGV_Status = _reflection.GeneratedProtocolMessageType('UGV_Status', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _UGV_STATUS, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.UGV_Status) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(UGV_Status) |
||||||
|
|
||||||
|
UGV_Message = _reflection.GeneratedProtocolMessageType('UGV_Message', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _UGV_MESSAGE, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.UGV_Message) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(UGV_Message) |
||||||
|
|
||||||
|
DriveHeadingData = _reflection.GeneratedProtocolMessageType('DriveHeadingData', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _DRIVEHEADINGDATA, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.DriveHeadingData) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(DriveHeadingData) |
||||||
|
|
||||||
|
GroundCommand = _reflection.GeneratedProtocolMessageType('GroundCommand', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _GROUNDCOMMAND, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.GroundCommand) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(GroundCommand) |
||||||
|
|
||||||
|
GroundMessage = _reflection.GeneratedProtocolMessageType('GroundMessage', (_message.Message,), dict( |
||||||
|
DESCRIPTOR = _GROUNDMESSAGE, |
||||||
|
__module__ = 'messages_pb2' |
||||||
|
# @@protoc_insertion_point(class_scope:ugv.messages.GroundMessage) |
||||||
|
)) |
||||||
|
_sym_db.RegisterMessage(GroundMessage) |
||||||
|
|
||||||
|
|
||||||
|
DESCRIPTOR._options = None |
||||||
|
# @@protoc_insertion_point(module_scope) |
@ -0,0 +1,14 @@ |
|||||||
|
certifi==2019.3.9 |
||||||
|
chardet==3.0.4 |
||||||
|
idna==2.8 |
||||||
|
netifaces==0.10.6 |
||||||
|
protobuf==3.7.1 |
||||||
|
PyCRC==1.21 |
||||||
|
pyserial==3.4 |
||||||
|
python-engineio==3.5.2 |
||||||
|
python-socketio==4.0.2 |
||||||
|
PyYAML==5.1 |
||||||
|
requests==2.22.0 |
||||||
|
six==1.12.0 |
||||||
|
urllib3==1.25.3 |
||||||
|
websocket-client==0.56.0 |
@ -0,0 +1,205 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
|
||||||
|
import logging |
||||||
|
import sys |
||||||
|
import serial |
||||||
|
import threading |
||||||
|
from threading import Thread |
||||||
|
import time |
||||||
|
import binascii |
||||||
|
from base64 import b64decode, b64encode |
||||||
|
from PyCRC.CRC32 import CRC32 |
||||||
|
import struct |
||||||
|
|
||||||
|
import messages_pb2 as messages |
||||||
|
from google.protobuf.message import Message |
||||||
|
|
||||||
|
log = logging.getLogger("ugv") |
||||||
|
|
||||||
|
|
||||||
|
class UGVComms: |
||||||
|
MAX_WRITE_RETRY = 5 |
||||||
|
RETRY_TIME = 1.5 |
||||||
|
|
||||||
|
def __init__(self, serial_port: serial.Serial, on_msg_received=None): |
||||||
|
self.ser = serial_port |
||||||
|
self.on_msg_received = on_msg_received |
||||||
|
self.msg_acks = [] |
||||||
|
self.ack_cv = threading.Condition() |
||||||
|
self.next_command_id = 1 |
||||||
|
self.last_status = None |
||||||
|
self.last_status_time = None |
||||||
|
self.rx_thread = None |
||||||
|
self.is_running = False |
||||||
|
self.log_file = None |
||||||
|
|
||||||
|
def write_base64(self, data: bytes): |
||||||
|
crc = CRC32().calculate(data) |
||||||
|
data_with_checksum = bytearray(data) |
||||||
|
data_with_checksum.extend(struct.pack('<L', crc)) |
||||||
|
encoded = b64encode(data_with_checksum) |
||||||
|
self.ser.write(encoded) |
||||||
|
self.ser.write(b'\n') |
||||||
|
|
||||||
|
def write_message(self, msg: Message): |
||||||
|
log.debug("writing message: %s", msg) |
||||||
|
data = msg.SerializeToString() |
||||||
|
self.write_base64(data) |
||||||
|
|
||||||
|
def write_command(self, command, retry=True): |
||||||
|
cmdid = self.next_command_id |
||||||
|
self.next_command_id += 1 |
||||||
|
|
||||||
|
gmsg = messages.GroundMessage() |
||||||
|
if type(command) is int: |
||||||
|
gmsg.command.type = command |
||||||
|
else: |
||||||
|
gmsg.command.CopyFrom(command) |
||||||
|
gmsg.command.id = cmdid |
||||||
|
self.write_message(gmsg) |
||||||
|
last_write_time = time.time() |
||||||
|
if not retry: |
||||||
|
return |
||||||
|
tries = UGVComms.MAX_WRITE_RETRY |
||||||
|
with self.ack_cv: |
||||||
|
while tries > 0: |
||||||
|
if cmdid in self.msg_acks: |
||||||
|
self.msg_acks.remove(cmdid) |
||||||
|
log.debug("received ack for command") |
||||||
|
return |
||||||
|
time_left = time.time() - last_write_time |
||||||
|
if time_left >= self.RETRY_TIME: |
||||||
|
log.warning("retry writing command") |
||||||
|
self.write_message(gmsg) |
||||||
|
last_write_time = time.time() |
||||||
|
tries -= 1 |
||||||
|
self.ack_cv.wait(timeout=time_left) |
||||||
|
raise TimeoutError("Timeout waiting for command ack") |
||||||
|
|
||||||
|
def read_message(self): |
||||||
|
data = self.ser.read_until(terminator=b'\n') |
||||||
|
if len(data) is 0: |
||||||
|
return None |
||||||
|
try: |
||||||
|
decoded = b64decode(data, validate=True) |
||||||
|
except binascii.Error: |
||||||
|
log.warning("read bad data: %s", data) |
||||||
|
self.ser.flush() |
||||||
|
return None |
||||||
|
if len(decoded) < 4: |
||||||
|
log.warning('Message too short ({} bytes)'.format(len(decoded))) |
||||||
|
return None |
||||||
|
msgcrc, = struct.unpack('<L', decoded[-4:]) |
||||||
|
calccrc = CRC32().calculate(decoded[:-4]) |
||||||
|
if msgcrc != calccrc: |
||||||
|
log.warning('Checksum did not match ({} != {})'.format(msgcrc, calccrc)) |
||||||
|
return None |
||||||
|
msg = messages.UGV_Message() |
||||||
|
msg.ParseFromString(decoded[:-4]) |
||||||
|
return msg |
||||||
|
|
||||||
|
def process_message(self, msg: messages.UGV_Message): |
||||||
|
if msg is None: |
||||||
|
return |
||||||
|
log.debug("received UGV message: %s", msg) |
||||||
|
if self.on_msg_received: |
||||||
|
self.on_msg_received(msg) |
||||||
|
if self.log_file: |
||||||
|
print('[{}] UGV_Message: {}'.format(time.strftime('%Y-%b-%d %H:%M:%S'), msg), file=self.log_file) |
||||||
|
if msg.HasField("command_ack"): |
||||||
|
with self.ack_cv: |
||||||
|
self.msg_acks.append(msg.command_ack) |
||||||
|
self.ack_cv.notify() |
||||||
|
elif msg.HasField("status"): |
||||||
|
self.last_status = msg.status |
||||||
|
self.last_status_time = time.time() |
||||||
|
else: |
||||||
|
log.warning("unknown UGV message: %s", msg) |
||||||
|
|
||||||
|
def start(self): |
||||||
|
if self.is_running: |
||||||
|
log.warning("RX thread already running") |
||||||
|
return False |
||||||
|
self.is_running = True |
||||||
|
self.rx_thread = Thread(target=self.__rx_thread_entry, daemon=True) |
||||||
|
self.rx_thread.start() |
||||||
|
log.debug("started RX thread") |
||||||
|
return True |
||||||
|
|
||||||
|
def stop(self): |
||||||
|
if not self.is_running: |
||||||
|
return False |
||||||
|
self.is_running = False |
||||||
|
self.ser.close() |
||||||
|
self.rx_thread.join() |
||||||
|
return True |
||||||
|
|
||||||
|
def save_logs(self, file): |
||||||
|
self.log_file = open(file, mode='a') |
||||||
|
|
||||||
|
def __rx_thread_entry(self): |
||||||
|
try: |
||||||
|
while self.is_running and self.ser.is_open: |
||||||
|
try: |
||||||
|
msg = self.read_message() |
||||||
|
self.process_message(msg) |
||||||
|
except serial.SerialException: |
||||||
|
if not self.ser.is_open or not self.is_running: # port was probably just closed |
||||||
|
return |
||||||
|
log.error("serial error", exc_info=True) |
||||||
|
return |
||||||
|
except Exception: |
||||||
|
log.error("error reading message", exc_info=True) |
||||||
|
continue |
||||||
|
finally: |
||||||
|
if self.log_file: |
||||||
|
self.log_file.close() |
||||||
|
|
||||||
|
|
||||||
|
def main(): |
||||||
|
if len(sys.argv) >= 2: |
||||||
|
ser_url = sys.argv[1] |
||||||
|
else: |
||||||
|
ser_url = "hwgrep://" |
||||||
|
ser = serial.serial_for_url(ser_url, baudrate=9600, parity=serial.PARITY_NONE, |
||||||
|
stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS, |
||||||
|
timeout=0.5) |
||||||
|
ugv = UGVComms(ser) |
||||||
|
ugv.start() |
||||||
|
time.sleep(0.2) |
||||||
|
try: |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_SET_TARGET |
||||||
|
cmd.target_location.latitude = 34.068415 |
||||||
|
cmd.target_location.longitude = -118.443217 |
||||||
|
# ugv.write_command(cmd) |
||||||
|
cmd.type = messages.CMD_SET_CONFIG |
||||||
|
cmd.config.angle_pid.kp = 0.10 |
||||||
|
cmd.config.angle_pid.ki = 0 # .00005 |
||||||
|
cmd.config.angle_pid.kd = 0.4 |
||||||
|
cmd.config.angle_pid.max_output = 0.5 |
||||||
|
cmd.config.angle_pid.max_i_error = 15.0 |
||||||
|
cmd.config.min_target_dist = 10.0 |
||||||
|
cmd.config.min_flip_pitch = 90.0 |
||||||
|
ugv.write_command(cmd) |
||||||
|
while True: |
||||||
|
if ugv.last_status is None or ugv.last_status.state is not messages.STATE_DRIVE_HEADING: |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_DRIVE_HEADING |
||||||
|
cmd.drive_heading.heading = -115.0 - 180 |
||||||
|
cmd.drive_heading.power = 0.3 |
||||||
|
ugv.write_command(cmd) |
||||||
|
time.sleep(2.0) |
||||||
|
except KeyboardInterrupt: |
||||||
|
ugv.write_command(messages.CMD_DISABLE) |
||||||
|
log.info("exiting...") |
||||||
|
finally: |
||||||
|
ugv.ser.flush() |
||||||
|
ugv.ser.close() |
||||||
|
ugv.stop() |
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
logging.basicConfig(format='%(asctime)s [%(name)s] %(levelname)s: %(message)s', datefmt='%Y-%b-%d %H:%M:%S') |
||||||
|
log.setLevel(logging.DEBUG) |
||||||
|
main() |
@ -0,0 +1,241 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
|
||||||
|
import sys |
||||||
|
import serial |
||||||
|
import time |
||||||
|
import logging |
||||||
|
import readline |
||||||
|
import yaml |
||||||
|
try: |
||||||
|
from yaml import CLoader as YamlLoader, CDumper as YamlDumper |
||||||
|
except ImportError: |
||||||
|
from yaml import Loader as YamlLoader, Dumper as YamlDumper |
||||||
|
import types |
||||||
|
|
||||||
|
from ugv import UGVComms |
||||||
|
import messages_pb2 as messages |
||||||
|
import config_pb2 |
||||||
|
|
||||||
|
log = logging.getLogger("ugv_cmd") |
||||||
|
|
||||||
|
|
||||||
|
def dict2pb(d, pb): |
||||||
|
for key in d: |
||||||
|
val = d[key] |
||||||
|
if isinstance(val, dict): |
||||||
|
dict2pb(val, getattr(pb, key)) |
||||||
|
else: |
||||||
|
setattr(pb, key, val) |
||||||
|
|
||||||
|
|
||||||
|
class CLI_CMD: |
||||||
|
def __init__(self, func, names=[], description=""): |
||||||
|
self.func = func |
||||||
|
self.names = names |
||||||
|
self.description = description |
||||||
|
|
||||||
|
|
||||||
|
cli_commands = [] |
||||||
|
|
||||||
|
|
||||||
|
def cli_cmd(names=None, description=""): |
||||||
|
def dec(fn: types.FunctionType): |
||||||
|
if dec.names is None: |
||||||
|
dec.names = [fn.__name__] |
||||||
|
cli_commands.append(CLI_CMD(fn, dec.names, dec.description)) |
||||||
|
return fn |
||||||
|
|
||||||
|
dec.names = names |
||||||
|
dec.description = description |
||||||
|
|
||||||
|
return dec |
||||||
|
|
||||||
|
|
||||||
|
class UGV_CLI: |
||||||
|
def __init__(self, on_msg_received=None): |
||||||
|
self.on_msg_received = on_msg_received |
||||||
|
self.is_running = False |
||||||
|
self.last_state = messages.STATE_IDLE |
||||||
|
self.commands = { |
||||||
|
'get_status': self.get_status, |
||||||
|
's': self.get_status, |
||||||
|
} |
||||||
|
self.ugv = None |
||||||
|
pass |
||||||
|
|
||||||
|
@cli_cmd(names=["help", "h", "?"], description="Print this help message") |
||||||
|
def help_msg(self): |
||||||
|
print("Commands:") |
||||||
|
for cmd in cli_commands: |
||||||
|
names = ", ".join(cmd.names).ljust(30, ' ') |
||||||
|
print("{}: {}".format(names, cmd.description)) |
||||||
|
print() |
||||||
|
|
||||||
|
@cli_cmd(names=["exit", "q", "C-d", "C-c"], description="Quit the program") |
||||||
|
def exit(self): |
||||||
|
self.is_running = False |
||||||
|
|
||||||
|
@cli_cmd(names=["disable", "d"], description="Disable the UGV") |
||||||
|
def disable(self): |
||||||
|
self.ugv.write_command(messages.CMD_DISABLE) |
||||||
|
|
||||||
|
@cli_cmd(names=["set_target", "st"], description="Set the target to <lat> <long>") |
||||||
|
def set_target(self, lat=34.068415, long=-118.443217): |
||||||
|
lat = float(lat) |
||||||
|
long = float(long) |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_SET_TARGET |
||||||
|
cmd.target_location.latitude = lat |
||||||
|
cmd.target_location.longitude = long |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
log.info("set target to (%f, %f)", lat, long) |
||||||
|
|
||||||
|
@cli_cmd(names=["set_config", "sc"], description="Load configuration from config.yml and send") |
||||||
|
def set_config(self, config_file_name="./tools/config.yml"): |
||||||
|
with open(config_file_name, 'r') as configfile: |
||||||
|
config = yaml.load(configfile, Loader=YamlLoader) |
||||||
|
|
||||||
|
if 'REVISION' in config: |
||||||
|
config_rev = config['REVISION'] |
||||||
|
del config['REVISION'] |
||||||
|
else: |
||||||
|
config_rev = 1 |
||||||
|
|
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_SET_CONFIG |
||||||
|
dict2pb(config, cmd.config) |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
log.info("updated config") |
||||||
|
|
||||||
|
@cli_cmd(names=["drive_heading", "dh"], description="Drive a <heading> with a forward <power>") |
||||||
|
def drive_heading(self, heading=65, power=0.0): |
||||||
|
heading = float(heading) |
||||||
|
power = float(power) |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_DRIVE_HEADING |
||||||
|
cmd.drive_heading.heading = heading |
||||||
|
cmd.drive_heading.power = power |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
log.info("driving heading %f at power %f", heading, power) |
||||||
|
|
||||||
|
@cli_cmd(names=["drive_to_target", "dt"], description="Drive to the drop target") |
||||||
|
def drive_to_target(self): |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_DRIVE_TO_TARGET |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
log.info("driving to target") |
||||||
|
|
||||||
|
@cli_cmd(names=["run_test", "rt"], description="Run test mode") |
||||||
|
def run_test(self): |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_TEST |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
log.info("running test mode") |
||||||
|
|
||||||
|
@cli_cmd(names=["last_status", "ls", "s"], description="Print the last status of the UGV") |
||||||
|
def last_status(self): |
||||||
|
if self.ugv.last_status_time is None: |
||||||
|
log.info("no status received") |
||||||
|
else: |
||||||
|
last_status_delay = time.time() - self.ugv.last_status_time |
||||||
|
log.info("last status (%.4f seconds ago): %s", |
||||||
|
last_status_delay, self.ugv.last_status) |
||||||
|
|
||||||
|
@cli_cmd(names=["get_status", "gs"], description="Get the current status of the UGV") |
||||||
|
def get_status(self): |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_GET_STATUS |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
self.last_status() |
||||||
|
|
||||||
|
@cli_cmd(names=["ping", "p"], description="Ping the UGV") |
||||||
|
def ping(self): |
||||||
|
cmd = messages.GroundCommand() |
||||||
|
cmd.type = messages.CMD_PING |
||||||
|
self.ugv.write_command(cmd) |
||||||
|
print("Received ping response") |
||||||
|
|
||||||
|
@cli_cmd(names=["save_logs", "sl"], description="Save logs to a file") |
||||||
|
def save_logs(self, file=None): |
||||||
|
if file is None: |
||||||
|
file = 'ugv_log.txt' |
||||||
|
self.ugv.save_logs(file) |
||||||
|
print("Saving logs to {}".format(file)) |
||||||
|
|
||||||
|
@staticmethod |
||||||
|
def find_command(name): |
||||||
|
for cmd in cli_commands: |
||||||
|
if name in cmd.names: |
||||||
|
return cmd |
||||||
|
return None |
||||||
|
|
||||||
|
@staticmethod |
||||||
|
def complete_command(text, state): |
||||||
|
options = [name for cmd in cli_commands for name in cmd.names if name.startswith(text)] |
||||||
|
if state < len(options): |
||||||
|
return options[state] |
||||||
|
else: |
||||||
|
return None |
||||||
|
|
||||||
|
def start(self): |
||||||
|
self.is_running = True |
||||||
|
|
||||||
|
if len(sys.argv) >= 2: |
||||||
|
ser_url = sys.argv[1] |
||||||
|
else: |
||||||
|
ser_url = "hwgrep://USB" |
||||||
|
ser = serial.serial_for_url(ser_url, baudrate=9600, parity=serial.PARITY_NONE, |
||||||
|
stopbits=serial.STOPBITS_ONE, bytesize=serial.EIGHTBITS, |
||||||
|
timeout=0.5) |
||||||
|
|
||||||
|
self.ugv = UGVComms(ser, self.on_msg_received) |
||||||
|
self.ugv.start() |
||||||
|
|
||||||
|
def run_cli(self): |
||||||
|
if self.ugv is None: |
||||||
|
self.start() |
||||||
|
|
||||||
|
readline.parse_and_bind("tab: complete") |
||||||
|
readline.set_completer(self.complete_command) |
||||||
|
last_line = None |
||||||
|
try: |
||||||
|
print("Run 'help' to find out what commands are available") |
||||||
|
while self.is_running: |
||||||
|
line = input("UGV> ") |
||||||
|
if len(line) is 0 and last_line is not None: |
||||||
|
print(last_line) |
||||||
|
line = last_line |
||||||
|
line_parts = line.split(' ') |
||||||
|
if len(line_parts) is 0: |
||||||
|
continue |
||||||
|
cmd = self.find_command(line_parts[0]) |
||||||
|
if cmd is None: |
||||||
|
print("Unknown command: '%s'" % line_parts[0]) |
||||||
|
continue |
||||||
|
last_line = line |
||||||
|
try: |
||||||
|
cmd.func(self, *line_parts[1:]) |
||||||
|
except KeyboardInterrupt: |
||||||
|
print("Command interrupted") |
||||||
|
except Exception as e: |
||||||
|
print("Error executing command: ", e) |
||||||
|
# TODO: continuously write state |
||||||
|
# while True: |
||||||
|
# if self.ugv.last_status is None or self.ugv.last_status.state is not messages.STATE_DRIVE_HEADING: |
||||||
|
except (KeyboardInterrupt, EOFError): |
||||||
|
self.exit() |
||||||
|
finally: |
||||||
|
log.info("disabling UGV...") |
||||||
|
try: |
||||||
|
self.ugv.write_command(messages.CMD_DISABLE) |
||||||
|
log.info("done. exiting") |
||||||
|
except KeyboardInterrupt: |
||||||
|
log.info("force exiting...") |
||||||
|
self.ugv.stop() |
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
logging.basicConfig( |
||||||
|
format='%(asctime)s [%(name)s] %(levelname)s: %(message)s', datefmt='%Y-%b-%d %H:%M:%S') |
||||||
|
logging.getLogger().setLevel(logging.INFO) |
||||||
|
UGV_CLI().run_cli() |
@ -0,0 +1,82 @@ |
|||||||
|
#!/usr/bin/env python3 |
||||||
|
import socketio |
||||||
|
import logging |
||||||
|
from base64 import b64encode |
||||||
|
from threading import Thread |
||||||
|
import time |
||||||
|
|
||||||
|
from ugv_cmd import UGV_CLI |
||||||
|
import messages_pb2 as messages |
||||||
|
from google.protobuf.message import Message |
||||||
|
|
||||||
|
log = logging.getLogger("ugv_to_ground") |
||||||
|
|
||||||
|
def encode_msg(msg: Message): |
||||||
|
data = msg.SerializeToString() |
||||||
|
return b64encode(data).decode('utf-8') |
||||||
|
|
||||||
|
|
||||||
|
def ping_thread_entry(ugv_cli): |
||||||
|
while ugv_cli.is_running and ugv_cli.ugv.ser.is_open: |
||||||
|
try: |
||||||
|
ugv_cli.get_status() |
||||||
|
time.sleep(5.0) |
||||||
|
except IOError as e: |
||||||
|
log.error("Error pinging UGV: {}".format(e)) |
||||||
|
|
||||||
|
def start_ugv_to_ground(): |
||||||
|
server_ip = 'localhost' |
||||||
|
|
||||||
|
sio = socketio.Client() |
||||||
|
|
||||||
|
def on_msg_received(msg: messages.UGV_Message): |
||||||
|
sio.emit('UGV_MESSAGE', encode_msg(msg), namespace='/ugv') |
||||||
|
pass |
||||||
|
|
||||||
|
ugv_cli = UGV_CLI(on_msg_received) |
||||||
|
ugv_cli.start() |
||||||
|
|
||||||
|
@sio.on('connect', namespace='/ugv') |
||||||
|
def on_connect(): |
||||||
|
log.info("connected to ground server") |
||||||
|
|
||||||
|
@sio.on('disconnect', namespace='/ugv') |
||||||
|
def on_disconnect(): |
||||||
|
log.info("disconnected from ground server!") |
||||||
|
|
||||||
|
@sio.on('SET_TARGET', namespace='/ugv') |
||||||
|
def set_target(msg): |
||||||
|
log.info("Setting UGV target") |
||||||
|
try: |
||||||
|
ugv_cli.set_target(msg['lat'], msg['lng']) |
||||||
|
except IOError as e: |
||||||
|
log.error("Error setting target: {}".format(e)) |
||||||
|
|
||||||
|
@sio.on('DRIVE_TO_TARGET', namespace='/ugv') |
||||||
|
def drive_to_target(): |
||||||
|
log.info("Driving to target!") |
||||||
|
try: |
||||||
|
ugv_cli.drive_to_target() |
||||||
|
except IOError as e: |
||||||
|
log.error("Error setting target: {}".format(e)) |
||||||
|
|
||||||
|
while True: |
||||||
|
try: |
||||||
|
sio.connect('http://'+server_ip+':8081', namespaces=['/ugv'], transports='websocket') |
||||||
|
break |
||||||
|
except: |
||||||
|
print("Can't connect to ground server. Retrying in 2 seconds...") |
||||||
|
sio.sleep(2) |
||||||
|
|
||||||
|
ping_thread = Thread(target=ping_thread_entry, args=(ugv_cli, ), daemon=True) |
||||||
|
ping_thread.start() |
||||||
|
|
||||||
|
ugv_cli.run_cli() |
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__": |
||||||
|
logging.basicConfig(format='%(asctime)s [%(name)s] %(levelname)s: %(message)s', datefmt='%Y-%b-%d %H:%M:%S') |
||||||
|
logging.getLogger().setLevel(logging.INFO) |
||||||
|
|
||||||
|
start_ugv_to_ground() |
||||||
|
|
|
|
|
Loading…
Reference in new issue