mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_ToshibaCAN: add accessors for use by scripts
This commit is contained in:
parent
2bc91cbc4d
commit
415ba0f40d
@ -552,6 +552,15 @@ void AP_ToshibaCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
|
||||
}
|
||||
}
|
||||
|
||||
// return total usage time in seconds
|
||||
uint32_t AP_ToshibaCAN::get_usage_seconds(uint8_t esc_id) const
|
||||
{
|
||||
if (esc_id >= TOSHIBACAN_MAX_NUM_ESCS) {
|
||||
return 0;
|
||||
}
|
||||
return _telemetry[esc_id].usage_sec;
|
||||
}
|
||||
|
||||
// helper function to create motor_request_data_cmd_t
|
||||
AP_ToshibaCAN::motor_request_data_cmd_t AP_ToshibaCAN::get_motor_request_data_cmd(uint8_t request_id) const
|
||||
{
|
||||
|
@ -44,6 +44,9 @@ public:
|
||||
// return a bitmask of escs that are "present" which means they are responding to requests. Bitmask matches RC outputs
|
||||
uint16_t get_present_mask() const { return _esc_present_bitmask; }
|
||||
|
||||
// return total usage time in seconds
|
||||
uint32_t get_usage_seconds(uint8_t esc_id) const;
|
||||
|
||||
private:
|
||||
|
||||
// loop to send output to ESCs in background thread
|
||||
|
Loading…
Reference in New Issue
Block a user