1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-22 07:45:29 +03:00

Enable using the 'heading' field in MAVlink to display mAh used

This commit is contained in:
Markus Jevring 2018-08-06 20:24:13 +02:00
parent efb340f4c6
commit 131d46c850
4 changed files with 21 additions and 2 deletions

View file

@ -885,6 +885,12 @@ const clivalue_t valueTable[] = {
#if defined(USE_TELEMETRY_SMARTPORT) #if defined(USE_TELEMETRY_SMARTPORT)
{ "smartport_use_extra_sensors", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, smartport_use_extra_sensors)}, { "smartport_use_extra_sensors", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, smartport_use_extra_sensors)},
#endif #endif
#ifdef USE_TELEMETRY_MAVLINK
// Support for misusing the heading field in MAVlink to indicate mAh drawn for Connex Prosight OSD
// Set to 10 to show a tenth of your capacity drawn.
// Set to $size_of_battery to get a percentage of battery used.
{ "mavlink_mah_as_heading_divisor", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 30000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, mavlink_mah_as_heading_divisor) },
#endif
#endif // USE_TELEMETRY #endif // USE_TELEMETRY
// PG_LED_STRIP_CONFIG // PG_LED_STRIP_CONFIG

View file

@ -136,6 +136,17 @@ static void mavlinkSerialWrite(uint8_t * buf, uint16_t length)
serialWrite(mavlinkPort, buf[i]); serialWrite(mavlinkPort, buf[i]);
} }
static int16_t headingOrScaledMilliAmpereHoursDrawn(void)
{
if (isAmperageConfigured() && telemetryConfig()->mavlink_mah_as_heading_divisor > 0) {
// In the Connex Prosight OSD, this goes between 0 and 999, so it will need to be scaled in that range.
return getMAhDrawn() / telemetryConfig()->mavlink_mah_as_heading_divisor;
}
// heading Current heading in degrees, in compass units (0..360, 0=north)
return DECIDEGREES_TO_DEGREES(attitude.values.yaw);
}
void freeMAVLinkTelemetryPort(void) void freeMAVLinkTelemetryPort(void)
{ {
closeSerialPort(mavlinkPort); closeSerialPort(mavlinkPort);
@ -354,7 +365,7 @@ void mavlinkSendPosition(void)
// Ground Z Speed (Altitude), expressed as m/s * 100 // Ground Z Speed (Altitude), expressed as m/s * 100
0, 0,
// heading Current heading in degrees, in compass units (0..360, 0=north) // heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw) headingOrScaledMilliAmpereHoursDrawn()
); );
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg); msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);
mavlinkSerialWrite(mavBuffer, msgLength); mavlinkSerialWrite(mavBuffer, msgLength);
@ -433,7 +444,7 @@ void mavlinkSendHUDAndHeartbeat(void)
// groundspeed Current ground speed in m/s // groundspeed Current ground speed in m/s
mavGroundSpeed, mavGroundSpeed,
// heading Current heading in degrees, in compass units (0..360, 0=north) // heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw), headingOrScaledMilliAmpereHoursDrawn(),
// throttle Current throttle setting in integer percent, 0 to 100 // throttle Current throttle setting in integer percent, 0 to 100
scaleRange(constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX), PWM_RANGE_MIN, PWM_RANGE_MAX, 0, 100), scaleRange(constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX), PWM_RANGE_MIN, PWM_RANGE_MAX, 0, 100),
// alt Current altitude (MSL), in meters, if we have sonar or baro use them, otherwise use GPS (less accurate) // alt Current altitude (MSL), in meters, if we have sonar or baro use them, otherwise use GPS (less accurate)

View file

@ -77,6 +77,7 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
}, },
.smartport_use_extra_sensors = false, .smartport_use_extra_sensors = false,
.mavlink_mah_as_heading_divisor = 0,
); );
void telemetryInit(void) void telemetryInit(void)

View file

@ -54,6 +54,7 @@ typedef struct telemetryConfig_s {
uint8_t report_cell_voltage; uint8_t report_cell_voltage;
uint8_t flysky_sensors[IBUS_SENSOR_COUNT]; uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
uint8_t smartport_use_extra_sensors; uint8_t smartport_use_extra_sensors;
uint16_t mavlink_mah_as_heading_divisor;
} telemetryConfig_t; } telemetryConfig_t;
PG_DECLARE(telemetryConfig_t, telemetryConfig); PG_DECLARE(telemetryConfig_t, telemetryConfig);