mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
SRV_Channel: propagate ESC type into rcout
This commit is contained in:
parent
d23a0bc23d
commit
18366a4b6d
@ -13,6 +13,7 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Common/Bitmask.h>
|
||||
@ -470,6 +471,9 @@ public:
|
||||
// calculate PWM for all channels
|
||||
static void calc_pwm(void);
|
||||
|
||||
// return the ESC type for dshot commands
|
||||
static AP_HAL::RCOutput::DshotEscType get_dshot_esc_type() { return AP_HAL::RCOutput::DshotEscType(_singleton->dshot_esc_type.get()); }
|
||||
|
||||
static SRV_Channel *srv_channel(uint8_t i) {
|
||||
return i<NUM_SERVO_CHANNELS?&channels[i]:nullptr;
|
||||
}
|
||||
@ -578,6 +582,7 @@ private:
|
||||
AP_Int8 auto_trim;
|
||||
AP_Int16 default_rate;
|
||||
AP_Int8 dshot_rate;
|
||||
AP_Int8 dshot_esc_type;
|
||||
|
||||
// return true if passthrough is disabled
|
||||
static bool passthrough_disabled(void) {
|
||||
|
@ -202,6 +202,13 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_DSHOT_RATE", 23, SRV_Channels, dshot_rate, 0),
|
||||
|
||||
// @Param: _DSHOT_ESC
|
||||
// @DisplayName: Servo DShot ESC type
|
||||
// @Description: This sets the DShot ESC type for all outputs. The ESC type affects the range of DShot commands available. None means that no dshot commands will be executed.
|
||||
// @Values: 0:None,1:BLHeli32/BLHeli_S/Kiss
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_DSHOT_ESC", 24, SRV_Channels, dshot_esc_type, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -229,7 +236,6 @@ SRV_Channels::SRV_Channels(void)
|
||||
blheli_ptr = &blheli;
|
||||
#endif
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
}
|
||||
|
||||
// SRV_Channels initialization
|
||||
|
Loading…
Reference in New Issue
Block a user