1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Merge pull request #4978 from qba667/betaflight_ibus

Additional IBUS telemetry implemented.
This commit is contained in:
Michael Keller 2018-01-20 16:27:50 +13:00 committed by GitHub
commit c4b5748b8d
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 587 additions and 146 deletions

View file

@ -24,11 +24,16 @@ extern "C" {
#include "pg/pg.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "io/gps.h"
#include "flight/imu.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "telemetry/telemetry.h"
#include "telemetry/ibus.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/barometer.h"
#include "sensors/acceleration.h"
#include "scheduler/scheduler.h"
#include "fc/fc_tasks.h"
}
@ -38,9 +43,18 @@ extern "C" {
extern "C" {
uint8_t armingFlags = 0;
uint8_t stateFlags = 0;
uint16_t flightModeFlags = 0;
uint8_t testBatteryCellCount =3;
float rcCommand[4] = {0, 0, 0, 0};
telemetryConfig_t telemetryConfig_System;
batteryConfig_s batteryConfig_System;
attitudeEulerAngles_t attitude = EULER_INITIALIZE;
acc_t acc;
baro_t baro;
gpsSolutionData_t gpsSol;
uint16_t GPS_distanceToHome;
}
static int16_t gyroTemperature;
@ -54,6 +68,57 @@ uint16_t getVbat(void)
return vbat;
}
extern "C" {
static int32_t amperage = 100;
static int32_t estimatedVario = 0;
static uint8_t batteryRemaining = 0;
static uint16_t avgCellVoltage = vbat/testBatteryCellCount;
static throttleStatus_e throttleStatus = THROTTLE_HIGH;
static uint32_t definedFeatures = 0;
static uint32_t definedSensors = SENSOR_GYRO | SENSOR_ACC | SENSOR_MAG | SENSOR_SONAR | SENSOR_GPS | SENSOR_GPSMAG;
int32_t getAmperage(void)
{
return amperage;
}
int32_t getEstimatedVario(void)
{
return estimatedVario;
}
uint8_t calculateBatteryPercentageRemaining(void)
{
return batteryRemaining;
}
uint16_t getBatteryAverageCellVoltage(void)
{
return avgCellVoltage;
}
int32_t getMAhDrawn(void)
{
return 0;
}
throttleStatus_e calculateThrottleStatus(void)
{
return throttleStatus;
}
bool feature(uint32_t mask)
{
return (definedFeatures & mask) != 0;
}
bool sensors(sensors_e sensor)
{
return (definedSensors & sensor) != 0;
}
}
#define SERIAL_BUFFER_SIZE 256
typedef struct serialPortStub_s {
@ -202,6 +267,13 @@ void serialTestResetBuffers()
memset(&serialWriteStub, 0, sizeof(serialWriteStub));
}
void setTestSensors()
{
telemetryConfig_System.flysky_sensors[0] = 0x03;
telemetryConfig_System.flysky_sensors[1] = 0x01;
telemetryConfig_System.flysky_sensors[2] = 0x02;
telemetryConfig_System.flysky_sensors[3] = 0x00;
}
void serialTestResetPort()
{
@ -221,6 +293,7 @@ protected:
virtual void SetUp()
{
serialTestResetPort();
setTestSensors();
}
};