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

Merge pull request #1602 from McGiverGim/add_telem_info_motors

Add telemetry dshot data info to the motors tab
This commit is contained in:
Michael Keller 2019-08-30 01:19:01 +12:00 committed by GitHub
commit 19106ae6cb
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
7 changed files with 164 additions and 11 deletions

View file

@ -26,6 +26,7 @@ var SERVO_RULES;
var SERIAL_CONFIG;
var SENSOR_DATA;
var MOTOR_DATA;
var MOTOR_TELEMETRY_DATA;
var SERVO_DATA;
var GPS_DATA;
var ANALOG;
@ -210,6 +211,15 @@ var FC = {
MOTOR_DATA = new Array(8);
SERVO_DATA = new Array(8);
MOTOR_TELEMETRY_DATA = {
rpm: [0, 0, 0, 0, 0, 0, 0, 0],
invalidPercent: [0, 0, 0, 0, 0, 0, 0, 0],
temperature: [0, 0, 0, 0, 0, 0, 0, 0],
voltage: [0, 0, 0, 0, 0, 0, 0, 0],
current: [0, 0, 0, 0, 0, 0, 0, 0],
consumption: [0, 0, 0, 0, 0, 0, 0, 0],
};
GPS_DATA = {
fix: 0,
numSat: 0,
@ -277,6 +287,10 @@ var FC = {
minthrottle: 0,
maxthrottle: 0,
mincommand: 0,
motor_count: 0,
motor_poles: 0,
use_dshot_telemetry: false,
use_esc_sensor: false,
};
GPS_CONFIG = {

View file

@ -115,6 +115,8 @@ var MSPCodes = {
MSP_VTXTABLE_BAND: 137,
MSP_VTXTABLE_POWERLEVEL: 138,
MSP_MOTOR_TELEMETRY: 139,
MSP_STATUS_EX: 150,
MSP_UID: 160,

View file

@ -142,6 +142,17 @@ MspHelper.prototype.process_data = function(dataHandler) {
MOTOR_DATA[i] = data.readU16();
}
break;
case MSPCodes.MSP_MOTOR_TELEMETRY:
var telemMotorCount = data.readU8();
for (let i = 0; i < telemMotorCount; i++) {
MOTOR_TELEMETRY_DATA.rpm[i] = data.readU32(); // RPM
MOTOR_TELEMETRY_DATA.invalidPercent[i] = data.readU16(); // 10000 = 100.00%
MOTOR_TELEMETRY_DATA.temperature[i] = data.readU8(); // degrees celsius
MOTOR_TELEMETRY_DATA.voltage[i] = data.readU16(); // 0.01V per unit
MOTOR_TELEMETRY_DATA.current[i] = data.readU16(); // 0.01A per unit
MOTOR_TELEMETRY_DATA.consumption[i] = data.readU16(); // mAh
}
break;
case MSPCodes.MSP_RC:
RC.active_channels = data.byteLength / 2;
for (var i = 0; i < RC.active_channels; i++) {
@ -392,6 +403,12 @@ MspHelper.prototype.process_data = function(dataHandler) {
MOTOR_CONFIG.minthrottle = data.readU16(); // 0-2000
MOTOR_CONFIG.maxthrottle = data.readU16(); // 0-2000
MOTOR_CONFIG.mincommand = data.readU16(); // 0-2000
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
MOTOR_CONFIG.motor_count = data.readU8();
MOTOR_CONFIG.motor_poles = data.readU8();
MOTOR_CONFIG.use_dshot_telemetry = data.readU8() != 0;
MOTOR_CONFIG.use_esc_sensor = data.readU8() != 0;
}
break;
case MSPCodes.MSP_COMPASS_CONFIG:
COMPASS_CONFIG.mag_declination = data.read16() / 100; // -18000-18000
@ -1608,7 +1625,10 @@ MspHelper.prototype.crunch = function(code) {
buffer.push16(MOTOR_CONFIG.minthrottle)
.push16(MOTOR_CONFIG.maxthrottle)
.push16(MOTOR_CONFIG.mincommand);
break;
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
buffer.push8(MOTOR_CONFIG.motor_poles);
}
break;
case MSPCodes.MSP_SET_GPS_CONFIG:
buffer.push8(GPS_CONFIG.provider)
.push8(GPS_CONFIG.ublox_sbas);

View file

@ -45,7 +45,15 @@ TABS.motors.initialize = function (callback) {
}
function load_motor_data() {
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_mixer_config);
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_motor_telemetry_data);
}
function load_motor_telemetry_data() {
if (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor) {
MSP.send_message(MSPCodes.MSP_MOTOR_TELEMETRY, false, false, load_mixer_config);
} else {
load_mixer_config();
}
}
function load_mixer_config() {
@ -216,6 +224,15 @@ TABS.motors.initialize = function (callback) {
$('#motorsEnableTestMode').prop('checked', false);
if (semver.lt(CONFIG.apiVersion, "1.42.0") || !(MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor)) {
$(".motor_testing .telemetry").hide();
} else {
// Hide telemetry from unused motors (to hide the tooltip in an empty blank space)
for (let i = MOTOR_CONFIG.motor_count; i < MOTOR_DATA.length; i++) {
$(".motor_testing .telemetry .motor-" + i).hide();
}
}
update_model(MIXER_CONFIG.mixer);
// Always start with default/empty sensor data array, clean slate all
@ -434,7 +451,7 @@ TABS.motors.initialize = function (callback) {
}
var motors_wrapper = $('.motors .bar-wrapper'),
servos_wrapper = $('.servos .bar-wrapper');
servos_wrapper = $('.servos .bar-wrapper');
for (var i = 0; i < 8; i++) {
motors_wrapper.append('\
@ -592,7 +609,15 @@ TABS.motors.initialize = function (callback) {
}
function get_motor_data() {
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, get_servo_data);
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, get_motor_telemetry_data);
}
function get_motor_telemetry_data() {
if (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor) {
MSP.send_message(MSPCodes.MSP_MOTOR_TELEMETRY, false, false, get_servo_data);
} else {
get_servo_data();
}
}
function get_servo_data() {
@ -618,6 +643,48 @@ TABS.motors.initialize = function (callback) {
'height' : height + 'px',
'background-color' : 'rgba(255,187,0,1.'+ color +')'
});
if (i < MOTOR_CONFIG.motor_count && (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor)) {
const MAX_INVALID_PERCENT = 100,
MAX_VALUE_SIZE = 6;
let rpmMotorValue = MOTOR_TELEMETRY_DATA.rpm[i];
// Reduce the size of the value if too big
if (rpmMotorValue > 999999) {
rpmMotorValue = (rpmMotorValue / 1000000).toFixed(5 - (rpmMotorValue / 1000000).toFixed(0).toString().length) + "M";
}
rpmMotorValue = rpmMotorValue.toString().padStart(MAX_VALUE_SIZE);
let telemetryText = i18n.getMessage('motorsRPM', {motorsRpmValue: rpmMotorValue});
if (MOTOR_CONFIG.use_dshot_telemetry) {
let invalidPercent = MOTOR_TELEMETRY_DATA.invalidPercent[i];
let classError = (invalidPercent > MAX_INVALID_PERCENT) ? "warning" : "";
invalidPercent = (invalidPercent / 100).toFixed(2).toString().padStart(MAX_VALUE_SIZE);
telemetryText += "<br><span class='" + classError + "'>";
telemetryText += i18n.getMessage('motorsRPMError', {motorsErrorValue: invalidPercent});
telemetryText += "</span>";
}
if (MOTOR_CONFIG.use_esc_sensor) {
let escTemperature = MOTOR_TELEMETRY_DATA.temperature[i];
telemetryText += "<br>";
escTemperature = escTemperature.toString().padStart(MAX_VALUE_SIZE);
telemetryText += i18n.getMessage('motorsESCTemperature', {motorsESCTempValue: escTemperature});
}
$('.motor_testing .telemetry .motor-' + i).html(telemetryText);
}
}
// servo indicators are still using old (not flexible block scale), it will be changed in the future accordingly