Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_ESC_Telem: log DroneCAN power percentage in extended ESC message #27771

Merged
merged 2 commits into from
Aug 7, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 8 additions & 1 deletion libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1447,14 +1447,21 @@ void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavc
.temperature_cdeg = int16_t((KELVIN_TO_C(msg.temperature)) * 100),
.voltage = msg.voltage,
.current = msg.current,
#if AP_EXTENDED_ESC_TELEM_ENABLED
.power_percentage = msg.power_rating_pct,
#endif
};

update_rpm(esc_index, msg.rpm, msg.error_count);
update_telem_data(esc_index, t,
(isnan(msg.current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT)
| (isnan(msg.voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)
| (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE));
| (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)
#if AP_EXTENDED_ESC_TELEM_ENABLED
| AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE
#endif
);
#endif // HAL_WITH_ESC_TELEM
}

#if AP_EXTENDED_ESC_TELEM_ENABLED
Expand Down
18 changes: 12 additions & 6 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
_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

#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
Expand Down Expand Up @@ -657,7 +660,8 @@ void AP_ESC_Telem::update()
const bool has_ext_data = telemdata.types &
(AP_ESC_Telem_Backend::TelemetryType::INPUT_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) {
// @LoggerMessage: ESCX
// @Description: ESC extended telemetry data
Expand All @@ -666,16 +670,18 @@ void AP_ESC_Telem::update()
// @Field: inpct: input duty cycle in percent
// @Field: outpct: output duty cycle in percent
// @Field: flags: manufacturer-specific status flags
// @Field: Pwr: Power percentage
AP::logger().WriteStreaming("ESCX",
"TimeUS,Instance,inpct,outpct,flags",
"s" "#" "%" "%" "-",
"F" "-" "-" "-" "-",
"Q" "B" "B" "B" "I",
"TimeUS,Instance,inpct,outpct,flags,Pwr",
"s" "#" "%" "%" "-" "%",
"F" "-" "-" "-" "-" "-",
"Q" "B" "B" "B" "I" "B",
AP_HAL::micros64(),
i,
telemdata.input_duty,
telemdata.output_duty,
telemdata.flags);
telemdata.flags,
telemdata.power_percentage);
}
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
}
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ class AP_ESC_Telem_Backend {
uint8_t input_duty; // input duty cycle
uint8_t output_duty; // output duty cycle
uint32_t flags; // Status flags
uint8_t power_percentage; // Percentage of output power
#endif // AP_EXTENDED_ESC_TELEM_ENABLED

// return true if the data is stale
Expand Down Expand Up @@ -58,7 +59,8 @@ class AP_ESC_Telem_Backend {
#if AP_EXTENDED_ESC_TELEM_ENABLED
INPUT_DUTY = 1 << 10,
OUTPUT_DUTY = 1 << 11,
FLAGS = 1 << 12
FLAGS = 1 << 12,
POWER_PERCENTAGE = 1 << 13,
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
};

Expand Down
Loading