AP_RPM: add DC_SEND_ID for periph RPM stream

This commit is contained in:
Iampete1 2024-03-14 00:09:20 +00:00 committed by Andrew Tridgell
parent 6dcb0af697
commit 23989bc569
4 changed files with 30 additions and 0 deletions

View File

@ -304,6 +304,18 @@ void AP_RPM::Log_RPM() const
} }
#endif #endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
// Return the sensor id to use for streaming over DroneCAN, negative number disables
int8_t AP_RPM::get_dronecan_sensor_id(uint8_t instance) const
{
if (!enabled(instance)) {
return -1;
}
return _params[instance].dronecan_sensor_id;
}
#endif
// singleton instance // singleton instance
AP_RPM *AP_RPM::_singleton; AP_RPM *AP_RPM::_singleton;

View File

@ -104,6 +104,11 @@ public:
// check settings are valid // check settings are valid
bool arming_checks(size_t buflen, char *buffer) const; bool arming_checks(size_t buflen, char *buffer) const;
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
// Return the sensor id to use for streaming over DroneCAN, negative number disables
int8_t get_dronecan_sensor_id(uint8_t instance) const;
#endif
private: private:
void convert_params(void); void convert_params(void);

View File

@ -78,6 +78,16 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = {
AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0), AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0),
#endif #endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
// @Param: DC_SEND_ID
// @DisplayName: DroneCAN Sensor ID
// @Description: DroneCAN sensor ID to send as on AP-Periph -1 disables
// @Range: -1 10
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("DC_SEND_ID", 9, AP_RPM_Params, dronecan_sensor_id, -1),
#endif
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -33,6 +33,9 @@ public:
#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED #if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED
AP_Int8 esc_telem_outbound_index; AP_Int8 esc_telem_outbound_index;
#endif #endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
AP_Int8 dronecan_sensor_id;
#endif
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];