mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
SRV_Channel: added SERVO_DEF_RATE parameter
this allows for the default rate of servo outputs to be set. This is needed for some planes where 50Hz isn't enough (eg. tailsitters)
This commit is contained in:
parent
5b43698e25
commit
4ca3546551
@ -391,6 +391,7 @@ private:
|
||||
|
||||
// this static arrangement is to avoid having static objects in AP_Param tables
|
||||
static SRV_Channel *channels;
|
||||
static SRV_Channels *instance;
|
||||
SRV_Channel obj_channels[NUM_SERVO_CHANNELS];
|
||||
|
||||
static struct srv_function {
|
||||
@ -402,6 +403,7 @@ private:
|
||||
} functions[SRV_Channel::k_nr_aux_servo_functions];
|
||||
|
||||
AP_Int8 auto_trim;
|
||||
AP_Int16 default_rate;
|
||||
|
||||
// return true if passthrough is disabled
|
||||
static bool passthrough_disabled(void) {
|
||||
|
@ -151,6 +151,8 @@ void SRV_Channels::update_aux_servo_function(void)
|
||||
/// Should be called after the the servo functions have been initialized
|
||||
void SRV_Channels::enable_aux_servos()
|
||||
{
|
||||
hal.rcout->set_default_rate(uint16_t(instance->default_rate.get()));
|
||||
|
||||
update_aux_servo_function();
|
||||
|
||||
// enable all channels that are set to a valid function. This
|
||||
|
@ -25,6 +25,7 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
SRV_Channel *SRV_Channels::channels;
|
||||
SRV_Channels *SRV_Channels::instance;
|
||||
bool SRV_Channels::disabled_passthrough;
|
||||
bool SRV_Channels::initialised;
|
||||
Bitmask SRV_Channels::function_mask{SRV_Channel::k_nr_aux_servo_functions};
|
||||
@ -102,6 +103,14 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
|
||||
|
||||
// @Param: _DEF_RATE
|
||||
// @DisplayName: Default output rate
|
||||
// @Description: This sets the default output rate in Hz for all outputs.
|
||||
// @Range: 25 400
|
||||
// @User: Advanced
|
||||
// @Units: Hz
|
||||
AP_GROUPINFO("_DEF_RATE", 18, SRV_Channels, default_rate, 50),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -110,6 +119,7 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
||||
*/
|
||||
SRV_Channels::SRV_Channels(void)
|
||||
{
|
||||
instance = this;
|
||||
channels = obj_channels;
|
||||
|
||||
// set defaults from the parameter table
|
||||
|
Loading…
Reference in New Issue
Block a user