RangingSensor and bug fixed
Implemented RangingSensor driver and choice between barometer and RangingSensor. Reduced I/O load.
This commit is contained in:
@@ -12,10 +12,10 @@
|
|||||||
default_envs = esp32dev
|
default_envs = esp32dev
|
||||||
|
|
||||||
[common]
|
[common]
|
||||||
lib_deps_builtin =
|
lib_deps_builtin =
|
||||||
Wire
|
Wire
|
||||||
BluetoothSerial
|
BluetoothSerial
|
||||||
lib_deps_external =
|
lib_deps_external =
|
||||||
https://git.gogacoder.com/gogacoder/GyverBME280.git @ ~1.5.0
|
https://git.gogacoder.com/gogacoder/GyverBME280.git @ ~1.5.0
|
||||||
https://git.gogacoder.com/gogacoder/MPU6050.git @ ~1.0.0
|
https://git.gogacoder.com/gogacoder/MPU6050.git @ ~1.0.0
|
||||||
https://git.gogacoder.com/gogacoder/I2Cdev.git @ ~1.0.1
|
https://git.gogacoder.com/gogacoder/I2Cdev.git @ ~1.0.1
|
||||||
@@ -27,14 +27,14 @@ lib_deps_external =
|
|||||||
https://github.com/pololu/vl53l0x-arduino @ 1.3.1
|
https://github.com/pololu/vl53l0x-arduino @ 1.3.1
|
||||||
|
|
||||||
[env:esp32dev]
|
[env:esp32dev]
|
||||||
platform = espressif32
|
platform = espressif32 @ 6.5.0
|
||||||
board = esp32dev
|
board = esp32dev
|
||||||
framework = arduino
|
framework = arduino
|
||||||
lib_deps = ${common.lib_deps_external}
|
lib_deps = ${common.lib_deps_external}
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
board_build.partitions = huge_app.csv
|
board_build.partitions = huge_app.csv
|
||||||
build_src_flags =
|
build_src_flags =
|
||||||
-std=c++2a
|
-std=c++2a
|
||||||
-Wall
|
-Wall
|
||||||
-Wextra
|
-Wextra
|
||||||
-Werror=all
|
-Werror=all
|
||||||
|
|||||||
@@ -5,10 +5,11 @@
|
|||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
|
|
||||||
class Application {
|
class Application {
|
||||||
public:
|
public:
|
||||||
Application(FlightDispatcher *dispatcher) {
|
Application(FlightDispatcher *dispatcher) {
|
||||||
assert(dispatcher != nullptr);
|
assert(dispatcher != nullptr);
|
||||||
_dispatcher = dispatcher;
|
_dispatcher = dispatcher;
|
||||||
|
ESP_LOGI(_tag, "ESP_IDF version: %s", esp_get_idf_version());
|
||||||
ESP_LOGI(_tag, "Application startup complete");
|
ESP_LOGI(_tag, "Application startup complete");
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -20,7 +21,8 @@ class Application {
|
|||||||
ESP_LOGI(_tag, "Application destroyed");
|
ESP_LOGI(_tag, "Application destroyed");
|
||||||
delete _dispatcher;
|
delete _dispatcher;
|
||||||
}
|
}
|
||||||
private:
|
|
||||||
|
private:
|
||||||
FlightDispatcher *_dispatcher = nullptr;
|
FlightDispatcher *_dispatcher = nullptr;
|
||||||
static constexpr const char *_tag = "Application";
|
static constexpr const char *_tag = "Application";
|
||||||
};
|
};
|
||||||
@@ -2,20 +2,20 @@
|
|||||||
// PVS-Studio Static Code Analyzer for C, C++, C#, and Java: https://pvs-studio.com
|
// PVS-Studio Static Code Analyzer for C, C++, C#, and Java: https://pvs-studio.com
|
||||||
|
|
||||||
#define CONFIG_DISABLE_HAL_LOCKS 0
|
#define CONFIG_DISABLE_HAL_LOCKS 0
|
||||||
|
|
||||||
#include "Wire.h"
|
#include "Wire.h"
|
||||||
#include "board_pins.h"
|
#include "board_pins.h"
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
|
|
||||||
class BoardI2C : public TwoWire {
|
class BoardI2C : public TwoWire {
|
||||||
public:
|
public:
|
||||||
BoardI2C(volatile bool loop_on_fail = true) : TwoWire(0) {
|
BoardI2C(volatile bool loop_on_fail = true) : TwoWire(0) {
|
||||||
if (begin(I2C_SDA_PIN, I2C_SCL_PIN, 100000)) {
|
if (begin(I2C_SDA_PIN, I2C_SCL_PIN, 100000)) {
|
||||||
setTimeOut(50);
|
setTimeOut(10);
|
||||||
ESP_LOGI("I2CBus", "Bus initialized");
|
ESP_LOGI("I2CBus", "Bus initialized");
|
||||||
} else {
|
} else {
|
||||||
ESP_LOGE("I2CBus", "Failed to initialize the i2c software bus!");
|
ESP_LOGE("I2CBus", "Failed to initialize the i2c software bus!");
|
||||||
while (loop_on_fail)
|
while (loop_on_fail);
|
||||||
;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -49,6 +49,7 @@ void FlightController::tick() {
|
|||||||
break;
|
break;
|
||||||
case DeviceStatus::IsBoarding:
|
case DeviceStatus::IsBoarding:
|
||||||
/* TODO: implement boarding */
|
/* TODO: implement boarding */
|
||||||
|
_boarding();
|
||||||
break;
|
break;
|
||||||
case DeviceStatus::IsFlying:
|
case DeviceStatus::IsFlying:
|
||||||
/* TODO: implement flying */
|
/* TODO: implement flying */
|
||||||
@@ -169,6 +170,7 @@ void FlightController::stopAllRotors() {
|
|||||||
setRotor1Duty(0);
|
setRotor1Duty(0);
|
||||||
setRotor2Duty(0);
|
setRotor2Duty(0);
|
||||||
setRotor3Duty(0);
|
setRotor3Duty(0);
|
||||||
|
_status = DeviceStatus::Idle;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FlightController::setHeightControllerParams(float p, float i, float d) {
|
void FlightController::setHeightControllerParams(float p, float i, float d) {
|
||||||
|
|||||||
@@ -167,8 +167,8 @@ void FlightDispatcher::_pidSettingsOpened() {
|
|||||||
|
|
||||||
pkg.endObj();
|
pkg.endObj();
|
||||||
pkg.end();
|
pkg.end();
|
||||||
pkg.s = String(MessageType::PidSettings) + ";" + pkg.s + _message_delimeter;
|
pkg.s = String(MessageType::PidSettings) + ";" + pkg.s;
|
||||||
_bluetoothDispatcher->sendPackage(pkg.s.c_str(), strlen(pkg.s.c_str()));
|
_bluetoothDispatcher->sendPackage(pkg.s.c_str());
|
||||||
ESP_LOGI(_tag, "PID settings sended %s", pkg.s.c_str());
|
ESP_LOGI(_tag, "PID settings sended %s", pkg.s.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -186,6 +186,6 @@ void FlightDispatcher::_sendTelemetry() {
|
|||||||
package["zIn"] = state.mpuState.zInertial;
|
package["zIn"] = state.mpuState.zInertial;
|
||||||
package.endObj();
|
package.endObj();
|
||||||
package.end();
|
package.end();
|
||||||
package.s = String(MessageType::UpdatePackage) + ";" + package.s + _message_delimeter;
|
package.s = String(MessageType::UpdatePackage) + ";" + package.s;
|
||||||
_bluetoothDispatcher->sendPackage(package.s.c_str(), strlen((package.s.c_str())));
|
_bluetoothDispatcher->sendPackage(package.s.c_str());
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -7,32 +7,38 @@
|
|||||||
#include <map>
|
#include <map>
|
||||||
|
|
||||||
// Message type annotation for mobile app
|
// Message type annotation for mobile app
|
||||||
enum MessageType { UpdatePackage = 0, PidSettings };
|
enum MessageType {
|
||||||
|
UpdatePackage = 0, PidSettings
|
||||||
|
};
|
||||||
|
|
||||||
class FlightDispatcher {
|
class FlightDispatcher {
|
||||||
/* Deserialize state and update it in FlightController. */
|
/* Deserialize state and update it in FlightController. */
|
||||||
public:
|
public:
|
||||||
FlightDispatcher(BluetoothDispatcher *bluetoothDispatcher,
|
FlightDispatcher(BluetoothDispatcher *bluetoothDispatcher,
|
||||||
FlightController *flightController, volatile bool loop_on_fail = true);
|
FlightController *flightController, volatile bool loop_on_fail = true);
|
||||||
|
|
||||||
~FlightDispatcher();
|
~FlightDispatcher();
|
||||||
|
|
||||||
void tick();
|
void tick();
|
||||||
private:
|
|
||||||
|
private:
|
||||||
/* Telemetry flow */
|
/* Telemetry flow */
|
||||||
void _sendTelemetry();
|
void _sendTelemetry();
|
||||||
|
|
||||||
/* Events handlers */
|
/* Events handlers */
|
||||||
void _onNewDeviceConnected(BTAddress device);
|
void _onNewDeviceConnected(BTAddress device);
|
||||||
|
|
||||||
void _onNewMessageReceived(char *package);
|
void _onNewMessageReceived(char *package);
|
||||||
|
|
||||||
/* Requests handlers */
|
/* Requests handlers */
|
||||||
void _changeStatus(const DeviceStatus &newStatus);
|
void _changeStatus(const DeviceStatus &newStatus);
|
||||||
|
|
||||||
void _pidSettingsOpened();
|
void _pidSettingsOpened();
|
||||||
|
|
||||||
/* Compile time settings */
|
/* Compile time settings */
|
||||||
static constexpr const char *_tag = "FlightDispatcher";
|
static constexpr const char *_tag = "FlightDispatcher";
|
||||||
static constexpr const int _telemetryTimeIntervalMS = 200;
|
static constexpr const int _telemetryTimeIntervalMS = 200;
|
||||||
static constexpr const uint8_t _jsonMaxDepth = 5;
|
static constexpr const uint8_t _jsonMaxDepth = 5;
|
||||||
static constexpr const char *_message_delimeter = "\n";
|
|
||||||
|
|
||||||
uint32_t _telemetryTimer = millis();
|
uint32_t _telemetryTimer = millis();
|
||||||
BluetoothDispatcher *_bluetoothDispatcher;
|
BluetoothDispatcher *_bluetoothDispatcher;
|
||||||
|
|||||||
@@ -27,7 +27,7 @@ bool BluetoothDispatcher::initialize(volatile bool loop_on_fail, int readTimeout
|
|||||||
deviceConnectedCallback = [this](BTAddress device) {
|
deviceConnectedCallback = [this](BTAddress device) {
|
||||||
_onDeviceConnected(device);
|
_onDeviceConnected(device);
|
||||||
};
|
};
|
||||||
_controller->setTimeout(50);
|
_controller->setTimeout(readTimeoutMS);
|
||||||
bool success = _controller->begin(_device_name, false);
|
bool success = _controller->begin(_device_name, false);
|
||||||
if (!success) {
|
if (!success) {
|
||||||
ESP_LOGI(_tag, "Failed to initialize Bluetooth controller!");
|
ESP_LOGI(_tag, "Failed to initialize Bluetooth controller!");
|
||||||
@@ -40,7 +40,7 @@ bool BluetoothDispatcher::initialize(volatile bool loop_on_fail, int readTimeout
|
|||||||
}
|
}
|
||||||
|
|
||||||
void BluetoothDispatcher::onNewPackageReceived(NewPackageCallback newPackageReceivedCb) {
|
void BluetoothDispatcher::onNewPackageReceived(NewPackageCallback newPackageReceivedCb) {
|
||||||
_newPackageReceivedCb = newPackageReceivedCb;
|
_newPackageReceivedCb = std::move(newPackageReceivedCb);
|
||||||
}
|
}
|
||||||
|
|
||||||
void BluetoothDispatcher::tick(const char message_delimeter) {
|
void BluetoothDispatcher::tick(const char message_delimeter) {
|
||||||
@@ -93,11 +93,16 @@ void BluetoothDispatcher::_onDeviceConnected(BTAddress device) {
|
|||||||
|
|
||||||
void BluetoothDispatcher::onNewDeviceConnected(DeviceConnectedCb deviceConnectedCb) {
|
void BluetoothDispatcher::onNewDeviceConnected(DeviceConnectedCb deviceConnectedCb) {
|
||||||
/* Callback called if device connected successfully. */
|
/* Callback called if device connected successfully. */
|
||||||
_deviceConnectedCallback = deviceConnectedCb;
|
_deviceConnectedCallback = std::move(deviceConnectedCb);
|
||||||
}
|
}
|
||||||
|
|
||||||
void BluetoothDispatcher::sendPackage(const char *package, size_t size) {
|
void BluetoothDispatcher::sendPackage(const char *package) {
|
||||||
_controller->write((uint8_t *) package, size);
|
if (!_controller->connected())
|
||||||
|
return;
|
||||||
|
auto res = _controller->println(package);
|
||||||
|
if (res == 0) {
|
||||||
|
delay(10);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -26,18 +26,26 @@ typedef std::function<void(BTAddress device)> DeviceConnectedCb;
|
|||||||
typedef std::function<void(char *package)> NewPackageCallback;
|
typedef std::function<void(char *package)> NewPackageCallback;
|
||||||
|
|
||||||
class BluetoothDispatcher {
|
class BluetoothDispatcher {
|
||||||
public:
|
public:
|
||||||
BluetoothDispatcher(BluetoothSerial *controller, const char *device_name = "Helicopter");
|
BluetoothDispatcher(BluetoothSerial *controller, const char *device_name = "Helicopter");
|
||||||
bool initialize(volatile bool loop_on_fail = true, int readTimeoutMS = 2);
|
|
||||||
|
bool initialize(volatile bool loop_on_fail = true, int readTimeoutMS = 10);
|
||||||
|
|
||||||
void tick(const char message_delimeter = '\n');
|
void tick(const char message_delimeter = '\n');
|
||||||
|
|
||||||
void onNewPackageReceived(NewPackageCallback newPackageReceivedCb);
|
void onNewPackageReceived(NewPackageCallback newPackageReceivedCb);
|
||||||
|
|
||||||
void onNewDeviceConnected(DeviceConnectedCb deviceConnectedCb);
|
void onNewDeviceConnected(DeviceConnectedCb deviceConnectedCb);
|
||||||
void sendPackage(const char *package, size_t size);
|
|
||||||
|
void sendPackage(const char *package);
|
||||||
|
|
||||||
~BluetoothDispatcher();
|
~BluetoothDispatcher();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void _onConfirmRequest(uint16_t pin);
|
void _onConfirmRequest(uint16_t pin);
|
||||||
|
|
||||||
void _onAuthComplete(boolean success) const;
|
void _onAuthComplete(boolean success) const;
|
||||||
|
|
||||||
void _onDeviceConnected(BTAddress device);
|
void _onDeviceConnected(BTAddress device);
|
||||||
|
|
||||||
const char *_device_name = nullptr;
|
const char *_device_name = nullptr;
|
||||||
|
|||||||
@@ -6,7 +6,7 @@
|
|||||||
typedef std::function<void()> OnMeasuringFinishedCb;
|
typedef std::function<void()> OnMeasuringFinishedCb;
|
||||||
|
|
||||||
class Barometer {
|
class Barometer {
|
||||||
public:
|
public:
|
||||||
Barometer(GyverBME280 *bme) {
|
Barometer(GyverBME280 *bme) {
|
||||||
_bme = bme;
|
_bme = bme;
|
||||||
};
|
};
|
||||||
@@ -33,7 +33,10 @@ class Barometer {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void measureBaseAltitudeAsync(void) {
|
void measureBaseAltitudeAsync(void) {
|
||||||
|
_calibrationIterationsCounter = 0;
|
||||||
|
_calibrationTimer = millis();
|
||||||
_isCalibration = true;
|
_isCalibration = true;
|
||||||
|
_startedAltitude = 0.f;
|
||||||
}
|
}
|
||||||
|
|
||||||
float altitude() /* [cm] */ {
|
float altitude() /* [cm] */ {
|
||||||
@@ -41,11 +44,13 @@ class Barometer {
|
|||||||
}
|
}
|
||||||
|
|
||||||
float flightHeight() /* [cm] */ {
|
float flightHeight() /* [cm] */ {
|
||||||
return altitude() - _startedAltitude;
|
if (_isCalibration)
|
||||||
|
return 0.f;
|
||||||
|
else return round(altitude() - _startedAltitude);
|
||||||
}
|
}
|
||||||
|
|
||||||
void onMeasuaringHeightFinished(OnMeasuringFinishedCb callback) {
|
void onMeasuaringHeightFinished(OnMeasuringFinishedCb callback) {
|
||||||
_measuaringHeightFinishedCb = callback;
|
_measuaringHeightFinishedCb = std::move(callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
void tick() {
|
void tick() {
|
||||||
@@ -63,13 +68,13 @@ class Barometer {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
GyverBME280 *_bme;
|
GyverBME280 *_bme;
|
||||||
float _startedAltitude = 0;
|
float _startedAltitude = 0.f;
|
||||||
bool _isCalibration = false;
|
bool _isCalibration = false;
|
||||||
uint32_t _calibrationTimer = 0;
|
uint32_t _calibrationTimer = 0;
|
||||||
int _calibrationIterationsCounter = 0;
|
int _calibrationIterationsCounter = 0;
|
||||||
OnMeasuringFinishedCb _measuaringHeightFinishedCb = nullptr;
|
OnMeasuringFinishedCb _measuaringHeightFinishedCb = nullptr;
|
||||||
static constexpr int _calibrationIterationsCount = 1500;
|
static constexpr int _calibrationIterationsCount = 1000;
|
||||||
static constexpr int _calibrationIterationDelay = 1; // [ms]
|
static constexpr int _calibrationIterationDelay = 1; // [ms]
|
||||||
};
|
};
|
||||||
@@ -3,8 +3,9 @@
|
|||||||
|
|
||||||
#include "board_pins.h"
|
#include "board_pins.h"
|
||||||
|
|
||||||
|
|
||||||
class BatteryController {
|
class BatteryController {
|
||||||
public:
|
public:
|
||||||
BatteryController(const uint16_t batteryPin, const uint16_t battery_data_switch_pin) {
|
BatteryController(const uint16_t batteryPin, const uint16_t battery_data_switch_pin) {
|
||||||
_battery_pin = batteryPin;
|
_battery_pin = batteryPin;
|
||||||
_battery_data_switch_pin = battery_data_switch_pin;
|
_battery_data_switch_pin = battery_data_switch_pin;
|
||||||
@@ -29,7 +30,7 @@ class BatteryController {
|
|||||||
return constrain(round(percent), 0, 100);
|
return constrain(round(percent), 0, 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint16_t _battery_pin;
|
uint16_t _battery_pin;
|
||||||
uint16_t _battery_data_switch_pin;
|
uint16_t _battery_data_switch_pin;
|
||||||
static constexpr const char *_tag = "BatteryController";
|
static constexpr const char *_tag = "BatteryController";
|
||||||
|
|||||||
43
src/Sensors/RangingSensor.cpp
Normal file
43
src/Sensors/RangingSensor.cpp
Normal file
@@ -0,0 +1,43 @@
|
|||||||
|
//
|
||||||
|
// Created by gogacoder on 10.03.24.
|
||||||
|
//
|
||||||
|
|
||||||
|
#include "RangingSensor.hpp"
|
||||||
|
#include "esp_log.h"
|
||||||
|
|
||||||
|
RangingSensor::RangingSensor(TwoWire &i2c, volatile bool loop_on_fail) {
|
||||||
|
_sensor = VL53L0X();
|
||||||
|
_sensor.setBus(&i2c);
|
||||||
|
if (_sensor.init()) {
|
||||||
|
_sensor.setMeasurementTimingBudget(20000);
|
||||||
|
_sensor.setTimeout(25);
|
||||||
|
ESP_LOGI(_tag, "Sensor initialized");
|
||||||
|
} else {
|
||||||
|
ESP_LOGE(_tag, "Failed to initialize RangingSensor!");
|
||||||
|
while (loop_on_fail) {}
|
||||||
|
}
|
||||||
|
_sensor.startContinuous(10);
|
||||||
|
}
|
||||||
|
|
||||||
|
void RangingSensor::startFlight() {
|
||||||
|
_start_distance = _distance;
|
||||||
|
}
|
||||||
|
|
||||||
|
void RangingSensor::tick() {
|
||||||
|
_distance = (uint32_t) round(runMiddleArifm((float) _sensor.readRangeContinuousMillimeters())) / 10;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t RangingSensor::getDistance() {
|
||||||
|
return _distance - _start_distance;
|
||||||
|
}
|
||||||
|
|
||||||
|
float RangingSensor::runMiddleArifm(float newVal) {
|
||||||
|
static int t = 0;
|
||||||
|
static float vals[_MID_ARITM_WINDOW];
|
||||||
|
static float average = 0;
|
||||||
|
if (++t >= _MID_ARITM_WINDOW) t = 0; // перемотка t
|
||||||
|
average -= vals[t]; // вычитаем старое
|
||||||
|
average += newVal; // прибавляем новое
|
||||||
|
vals[t] = newVal; // запоминаем в массив
|
||||||
|
return ((float) average / _MID_ARITM_WINDOW);
|
||||||
|
}
|
||||||
33
src/Sensors/RangingSensor.hpp
Normal file
33
src/Sensors/RangingSensor.hpp
Normal file
@@ -0,0 +1,33 @@
|
|||||||
|
//
|
||||||
|
// Created by gogacoder on 10.03.24.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef HELICOPTER_FIRMWARE_RANGINGSENSOR_H
|
||||||
|
#define HELICOPTER_FIRMWARE_RANGINGSENSOR_H
|
||||||
|
|
||||||
|
#include "Wire.h"
|
||||||
|
#include "VL53L0X.h"
|
||||||
|
|
||||||
|
class RangingSensor {
|
||||||
|
public:
|
||||||
|
RangingSensor(TwoWire &i2c, volatile bool loop_on_fail = true);
|
||||||
|
|
||||||
|
void tick();
|
||||||
|
|
||||||
|
void startFlight();
|
||||||
|
|
||||||
|
uint32_t getDistance();
|
||||||
|
|
||||||
|
private:
|
||||||
|
TwoWire *_i2c;
|
||||||
|
VL53L0X _sensor;
|
||||||
|
uint32_t _distance; // [cm]
|
||||||
|
uint32_t _start_distance = 0; // [cm]
|
||||||
|
static constexpr const char *_tag = "RangingSensor";
|
||||||
|
constexpr static const int _MID_ARITM_WINDOW = 5;
|
||||||
|
|
||||||
|
float runMiddleArifm(float newVal);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif //HELICOPTER_FIRMWARE_RANGINGSENSOR_H
|
||||||
@@ -3,25 +3,27 @@
|
|||||||
|
|
||||||
#include "Sensors.hpp"
|
#include "Sensors.hpp"
|
||||||
|
|
||||||
Sensors::Sensors(Barometer *barometer, MPU *mpu, Kalman2DFilter *filter,
|
Sensors::Sensors(Barometer *barometer, RangingSensor *ranging_sensor, MPU *mpu, Kalman2DFilter *filter,
|
||||||
BatteryController *battery, volatile bool loop_on_fail) {
|
BatteryController *battery, HeightSensor heightSensor, volatile bool loop_on_fail) {
|
||||||
assert(barometer != nullptr);
|
assert(barometer != nullptr);
|
||||||
assert(mpu != nullptr);
|
assert(mpu != nullptr);
|
||||||
assert(filter != nullptr);
|
assert(filter != nullptr);
|
||||||
assert(battery != nullptr);
|
assert(battery != nullptr);
|
||||||
|
assert(ranging_sensor != nullptr);
|
||||||
|
|
||||||
_barometer = barometer;
|
_barometer = barometer;
|
||||||
_mpu = mpu;
|
_mpu = mpu;
|
||||||
_2d_filter = filter;
|
_2d_filter = filter;
|
||||||
_battery = battery;
|
_battery = battery;
|
||||||
|
_ranging_sensor = ranging_sensor;
|
||||||
|
_heightSensor = heightSensor;
|
||||||
|
|
||||||
ESP_LOGI(_tag, "Initialize BMP280...");
|
ESP_LOGI(_tag, "Initialize BMP280...");
|
||||||
if (_barometer->initialize()) {
|
if (_barometer->initialize()) {
|
||||||
ESP_LOGI(_tag, "BMP280 initialized");
|
ESP_LOGI(_tag, "BMP280 initialized");
|
||||||
} else {
|
} else {
|
||||||
ESP_LOGI(_tag, "BMP280 initialization failed!");
|
ESP_LOGI(_tag, "BMP280 initialization failed!");
|
||||||
while (loop_on_fail)
|
while (loop_on_fail);
|
||||||
;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ESP_LOGI(_tag, "Initialize MPU6050...");
|
ESP_LOGI(_tag, "Initialize MPU6050...");
|
||||||
@@ -29,12 +31,12 @@ Sensors::Sensors(Barometer *barometer, MPU *mpu, Kalman2DFilter *filter,
|
|||||||
ESP_LOGI(_tag, "MPU6050 initialized");
|
ESP_LOGI(_tag, "MPU6050 initialized");
|
||||||
} else {
|
} else {
|
||||||
ESP_LOGI(_tag, "MPU6050 initialization failed!");
|
ESP_LOGI(_tag, "MPU6050 initialization failed!");
|
||||||
while (loop_on_fail)
|
while (loop_on_fail);
|
||||||
;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
_battery->initialize();
|
_battery->initialize();
|
||||||
ESP_LOGI(_tag, "BatteryController initialized");
|
ESP_LOGI(_tag, "BatteryController initialized");
|
||||||
|
|
||||||
ESP_LOGI(_tag, "Sensors initialized");
|
ESP_LOGI(_tag, "Sensors initialized");
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -43,6 +45,7 @@ Sensors::~Sensors() {
|
|||||||
delete _mpu;
|
delete _mpu;
|
||||||
delete _2d_filter;
|
delete _2d_filter;
|
||||||
delete _battery;
|
delete _battery;
|
||||||
|
delete _ranging_sensor;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sensors::measureBaseAltitudeSync(void) {
|
void Sensors::measureBaseAltitudeSync(void) {
|
||||||
@@ -54,18 +57,26 @@ void Sensors::measureBaseAltitudeAsync(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
float Sensors::rawFlightHeight(void) const {
|
float Sensors::rawFlightHeight(void) const {
|
||||||
/* Returns flight height from barometer immediatly */
|
/* Returns flight height from barometer immediately */
|
||||||
return _barometer->flightHeight();
|
switch (_heightSensor) {
|
||||||
|
case HeightSensor::Hybrid:
|
||||||
|
if (_barometer->flightHeight() >= 200.f) {
|
||||||
|
return _barometer->flightHeight();
|
||||||
|
} else {
|
||||||
|
return (float) _ranging_sensor->getDistance();
|
||||||
|
}
|
||||||
|
case HeightSensor::BarometerOnly:
|
||||||
|
return _barometer->flightHeight();
|
||||||
|
case HeightSensor::RangeMeterOnly:
|
||||||
|
return (float) _ranging_sensor->getDistance();
|
||||||
|
default:
|
||||||
|
return _barometer->flightHeight();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
float Sensors::flightHeight(void) const {
|
float Sensors::flightHeight(void) const {
|
||||||
/* Returns flight height from cache immediatly */
|
/* Returns flight height from cache immediately */
|
||||||
if (_flightHeightFromBarometer == 0.f) {
|
return rawFlightHeight();
|
||||||
ESP_LOGW(_tag, "flightHeight called, but tick() has called never");
|
|
||||||
return rawFlightHeight();
|
|
||||||
} else {
|
|
||||||
return _flightHeightFromBarometer;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
MpuData Sensors::mpuData() const {
|
MpuData Sensors::mpuData() const {
|
||||||
@@ -79,22 +90,25 @@ bool Sensors::tick(void) {
|
|||||||
/* Super loop iteraion */
|
/* Super loop iteraion */
|
||||||
/* Return true on update */
|
/* Return true on update */
|
||||||
_barometer->tick();
|
_barometer->tick();
|
||||||
|
_ranging_sensor->tick();
|
||||||
bool err;
|
bool err;
|
||||||
bool isMpuDataReady = _mpu->tick(err);
|
bool isMpuDataReady = _mpu->tick(err);
|
||||||
if (isMpuDataReady and !err) {
|
if (isMpuDataReady and !err) {
|
||||||
_2d_filter->filter(_mpu->accZInertial(), _barometer->flightHeight(),
|
//_2d_filter->filter(_mpu->accZInertial(), _barometer->flightHeight(),
|
||||||
_flightHeightFromBarometer, _zVelocityAltitude);
|
// _flightHeightFromBarometer, _zVelocityAltitude);
|
||||||
_mpuData = { .ax = _mpu->ax(),
|
_flightHeightFromBarometer = rawFlightHeight();
|
||||||
.ay = _mpu->ay(),
|
_zVelocityAltitude = _mpu->accZInertial();
|
||||||
.az = _mpu->az(),
|
_mpuData = {.ax = _mpu->ax(),
|
||||||
.gx = _mpu->gx(),
|
.ay = _mpu->ay(),
|
||||||
.gy = _mpu->gy(),
|
.az = _mpu->az(),
|
||||||
.gz = _mpu->gz(),
|
.gx = _mpu->gx(),
|
||||||
.yaw = _mpu->yaw(),
|
.gy = _mpu->gy(),
|
||||||
.pitch = _mpu->pitch(),
|
.gz = _mpu->gz(),
|
||||||
.roll = _mpu->roll(),
|
.yaw = _mpu->yaw(),
|
||||||
.gravity = _mpu->gravityZ(),
|
.pitch = _mpu->pitch(),
|
||||||
.zInertial = _mpu->accZInertial() };
|
.roll = _mpu->roll(),
|
||||||
|
.gravity = _mpu->gravityZ(),
|
||||||
|
.zInertial = _mpu->accZInertial()};
|
||||||
return true;
|
return true;
|
||||||
} else if (err) {
|
} else if (err) {
|
||||||
ESP_LOGE(_tag, "Failed to get DMP data!");
|
ESP_LOGE(_tag, "Failed to get DMP data!");
|
||||||
|
|||||||
@@ -4,6 +4,7 @@
|
|||||||
#include "Barometer.hpp"
|
#include "Barometer.hpp"
|
||||||
#include "BatteryController.hpp"
|
#include "BatteryController.hpp"
|
||||||
#include "Filters/Kalman2DFilter.hpp"
|
#include "Filters/Kalman2DFilter.hpp"
|
||||||
|
#include "RangingSensor.hpp"
|
||||||
#include "MPU.hpp"
|
#include "MPU.hpp"
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
|
|
||||||
@@ -17,20 +18,31 @@ struct MpuData {
|
|||||||
float zInertial;
|
float zInertial;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum HeightSensor {
|
||||||
|
RangeMeterOnly,
|
||||||
|
BarometerOnly,
|
||||||
|
Hybrid
|
||||||
|
};
|
||||||
|
|
||||||
class Sensors {
|
class Sensors {
|
||||||
public:
|
public:
|
||||||
Sensors(Barometer *barometer, MPU *mpu, Kalman2DFilter *filter,
|
Sensors(Barometer *barometer, RangingSensor *rangingSensor, MPU *mpu, Kalman2DFilter *filter,
|
||||||
BatteryController *battery, bool loop_on_fail = true);
|
BatteryController *battery, HeightSensor heightSensor = Hybrid, bool loop_on_fail = true);
|
||||||
|
|
||||||
~Sensors();
|
~Sensors();
|
||||||
|
|
||||||
void measureBaseAltitudeSync(void);
|
void measureBaseAltitudeSync(void);
|
||||||
|
|
||||||
void measureBaseAltitudeAsync(void);
|
void measureBaseAltitudeAsync(void);
|
||||||
|
|
||||||
void onMeasuaringAltitudeFinished(OnMeasuringFinishedCb callback);
|
void onMeasuaringAltitudeFinished(OnMeasuringFinishedCb callback);
|
||||||
|
|
||||||
float rawFlightHeight(void) const;
|
float rawFlightHeight(void) const;
|
||||||
|
|
||||||
float flightHeight(void) const;
|
float flightHeight(void) const;
|
||||||
|
|
||||||
void startMpuCalibration();
|
void startMpuCalibration();
|
||||||
|
|
||||||
void onMpuCalibrationFinished(OnCalibrationFinishedCb callback);
|
void onMpuCalibrationFinished(OnCalibrationFinishedCb callback);
|
||||||
|
|
||||||
MpuData mpuData(void) const;
|
MpuData mpuData(void) const;
|
||||||
@@ -39,16 +51,18 @@ class Sensors {
|
|||||||
|
|
||||||
bool tick(void);
|
bool tick(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Barometer *_barometer = nullptr;
|
Barometer *_barometer = nullptr;
|
||||||
MPU *_mpu = nullptr;
|
MPU *_mpu = nullptr;
|
||||||
BatteryController *_battery = nullptr;
|
BatteryController *_battery = nullptr;
|
||||||
Kalman2DFilter *_2d_filter = nullptr;
|
Kalman2DFilter *_2d_filter = nullptr;
|
||||||
|
RangingSensor *_ranging_sensor = nullptr;
|
||||||
|
HeightSensor _heightSensor;
|
||||||
|
|
||||||
/* cached filtered values */
|
/* cached filtered values */
|
||||||
float _flightHeightFromBarometer = 0.f;
|
float _flightHeightFromBarometer = 0.f;
|
||||||
float _zVelocityAltitude = 0.f;
|
float _zVelocityAltitude = 0.f;
|
||||||
MpuData _mpuData = { 0.f };
|
MpuData _mpuData = {0.f};
|
||||||
|
|
||||||
|
|
||||||
static constexpr const char *_tag = "Sensors";
|
static constexpr const char *_tag = "Sensors";
|
||||||
|
|||||||
@@ -1,8 +1,6 @@
|
|||||||
// This is a personal academic project. Dear PVS-Studio, please check it.
|
// This is a personal academic project. Dear PVS-Studio, please check it.
|
||||||
// PVS-Studio Static Code Analyzer for C, C++, C#, and Java: https://pvs-studio.com
|
// PVS-Studio Static Code Analyzer for C, C++, C#, and Java: https://pvs-studio.com
|
||||||
|
|
||||||
#include "driver/adc.h"
|
|
||||||
|
|
||||||
#define I2C_SDA_PIN 21
|
#define I2C_SDA_PIN 21
|
||||||
#define I2C_SCL_PIN 18
|
#define I2C_SCL_PIN 18
|
||||||
#define MPU6050_INT_PIN 19
|
#define MPU6050_INT_PIN 19
|
||||||
|
|||||||
@@ -14,14 +14,18 @@ void setup() {
|
|||||||
new BluetoothDispatcher(new BluetoothSerial()),
|
new BluetoothDispatcher(new BluetoothSerial()),
|
||||||
new FlightController(
|
new FlightController(
|
||||||
new Sensors(new Barometer(new GyverBME280(i2c)),
|
new Sensors(new Barometer(new GyverBME280(i2c)),
|
||||||
|
new RangingSensor(i2c),
|
||||||
new MPU(new MPU6050(MPU6050_DEFAULT_ADDRESS, &i2c)),
|
new MPU(new MPU6050(MPU6050_DEFAULT_ADDRESS, &i2c)),
|
||||||
new Kalman2DFilter(10.f, 1.f, 1.8f),
|
new Kalman2DFilter(10.f, 1.f, 1.8f),
|
||||||
new BatteryController(BATTERY_DATA_PIN, BATTERY_DATA_SWITCH_PIN)),
|
new BatteryController(BATTERY_DATA_PIN, BATTERY_DATA_SWITCH_PIN),
|
||||||
|
HeightSensor::Hybrid),
|
||||||
new SavedPidRegulator(3.5f, 0.0015f, 0.01f, "HeightControl"), // height
|
new SavedPidRegulator(3.5f, 0.0015f, 0.01f, "HeightControl"), // height
|
||||||
new SavedPidRegulator(2.f, 12.f, 0.f, "YawControl"), // yaw
|
new SavedPidRegulator(2.f, 12.f, 0.f, "YawControl"), // yaw
|
||||||
new BrushedMotor(1, 2, 3, 4, 1),
|
new BrushedMotor(1, 2, 3, 4, 1),
|
||||||
new BrushedMotor(1, 2, 3, 4, 1),
|
new BrushedMotor(1, 2, 3, 4, 1),
|
||||||
new PIDController(0.6f, 3.5f, 0.03f, new BrushedMotor(1, 2, 3, 4, 3), "RollControl"), // pitch
|
new PIDController(0.6f, 3.5f, 0.03f,
|
||||||
|
new BrushedMotor(1, 2, 3, 4, 3),
|
||||||
|
"RollControl"), // pitch
|
||||||
true)));
|
true)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user