AP_ESC_Telem: add logging of power percentage
This commit is contained in:
parent
8ec3d0f0a9
commit
34549cf0cb
@ -502,6 +502,9 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem
|
|||||||
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) {
|
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) {
|
||||||
_telem_data[esc_index].flags = new_data.flags;
|
_telem_data[esc_index].flags = new_data.flags;
|
||||||
}
|
}
|
||||||
|
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE) {
|
||||||
|
_telem_data[esc_index].power_percentage = new_data.power_percentage;
|
||||||
|
}
|
||||||
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
|
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
|
||||||
|
|
||||||
#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
|
#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
|
||||||
@ -657,7 +660,8 @@ void AP_ESC_Telem::update()
|
|||||||
const bool has_ext_data = telemdata.types &
|
const bool has_ext_data = telemdata.types &
|
||||||
(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY |
|
(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY |
|
||||||
AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY |
|
AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY |
|
||||||
AP_ESC_Telem_Backend::TelemetryType::FLAGS);
|
AP_ESC_Telem_Backend::TelemetryType::FLAGS |
|
||||||
|
AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE);
|
||||||
if (has_ext_data) {
|
if (has_ext_data) {
|
||||||
// @LoggerMessage: ESCX
|
// @LoggerMessage: ESCX
|
||||||
// @Description: ESC extended telemetry data
|
// @Description: ESC extended telemetry data
|
||||||
@ -666,16 +670,18 @@ void AP_ESC_Telem::update()
|
|||||||
// @Field: inpct: input duty cycle in percent
|
// @Field: inpct: input duty cycle in percent
|
||||||
// @Field: outpct: output duty cycle in percent
|
// @Field: outpct: output duty cycle in percent
|
||||||
// @Field: flags: manufacturer-specific status flags
|
// @Field: flags: manufacturer-specific status flags
|
||||||
|
// @Field: Pwr: Power percentage
|
||||||
AP::logger().WriteStreaming("ESCX",
|
AP::logger().WriteStreaming("ESCX",
|
||||||
"TimeUS,Instance,inpct,outpct,flags",
|
"TimeUS,Instance,inpct,outpct,flags,Pwr",
|
||||||
"s" "#" "%" "%" "-",
|
"s" "#" "%" "%" "-" "%",
|
||||||
"F" "-" "-" "-" "-",
|
"F" "-" "-" "-" "-" "-",
|
||||||
"Q" "B" "B" "B" "I",
|
"Q" "B" "B" "B" "I" "B",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
i,
|
i,
|
||||||
telemdata.input_duty,
|
telemdata.input_duty,
|
||||||
telemdata.output_duty,
|
telemdata.output_duty,
|
||||||
telemdata.flags);
|
telemdata.flags,
|
||||||
|
telemdata.power_percentage);
|
||||||
}
|
}
|
||||||
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
|
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
|
||||||
}
|
}
|
||||||
|
@ -27,6 +27,7 @@ public:
|
|||||||
uint8_t input_duty; // input duty cycle
|
uint8_t input_duty; // input duty cycle
|
||||||
uint8_t output_duty; // output duty cycle
|
uint8_t output_duty; // output duty cycle
|
||||||
uint32_t flags; // Status flags
|
uint32_t flags; // Status flags
|
||||||
|
uint8_t power_percentage; // Percentage of output power
|
||||||
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
|
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
|
||||||
|
|
||||||
// return true if the data is stale
|
// return true if the data is stale
|
||||||
@ -58,7 +59,8 @@ public:
|
|||||||
#if AP_EXTENDED_ESC_TELEM_ENABLED
|
#if AP_EXTENDED_ESC_TELEM_ENABLED
|
||||||
INPUT_DUTY = 1 << 10,
|
INPUT_DUTY = 1 << 10,
|
||||||
OUTPUT_DUTY = 1 << 11,
|
OUTPUT_DUTY = 1 << 11,
|
||||||
FLAGS = 1 << 12
|
FLAGS = 1 << 12,
|
||||||
|
POWER_PERCENTAGE = 1 << 13,
|
||||||
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
|
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user