SRV_Channel: minor formatting fixes

no functional change
This commit is contained in:
Randy Mackay 2017-07-25 12:23:09 +09:00
parent 298eaaeb3e
commit 572df8b859
4 changed files with 23 additions and 32 deletions

View File

@ -54,7 +54,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
AP_GROUPINFO("TRIM", 3, SRV_Channel, servo_trim, 1500), AP_GROUPINFO("TRIM", 3, SRV_Channel, servo_trim, 1500),
// @Param: REVERSED // @Param: REVERSED
// @DisplayName: Servo reverse // @DisplayName: Servo reverse
// @Description: Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel. // @Description: Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
@ -68,7 +68,7 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = {
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1,86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2,19:Elevator,21:Rudder,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:EPM,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:MotorTilt,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,68:Choke,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:tiltMotorLeft,76:tiltMotorRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle,82:Motor9,83:Motor10,84:Motor11,85:Motor12 // @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1,86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2,19:Elevator,21:Rudder,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:EPM,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:MotorTilt,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,68:Choke,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:tiltMotorLeft,76:tiltMotorRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle,82:Motor9,83:Motor10,84:Motor11,85:Motor12
// @User: Standard // @User: Standard
AP_GROUPINFO("FUNCTION", 5, SRV_Channel, function, 0), AP_GROUPINFO("FUNCTION", 5, SRV_Channel, function, 0),
AP_GROUPEND AP_GROUPEND
}; };
@ -80,7 +80,6 @@ SRV_Channel::SRV_Channel(void)
have_pwm_mask = ~uint16_t(0); have_pwm_mask = ~uint16_t(0);
} }
// convert a 0..range_max to a pwm // convert a 0..range_max to a pwm
uint16_t SRV_Channel::pwm_from_range(int16_t scaled_value) const uint16_t SRV_Channel::pwm_from_range(int16_t scaled_value) const
{ {

View File

@ -182,7 +182,7 @@ private:
// set_range() or set_angle() has been called // set_range() or set_angle() has been called
bool type_setup:1; bool type_setup:1;
// the hal channel number // the hal channel number
uint8_t ch_num; uint8_t ch_num;
@ -209,7 +209,7 @@ private:
// get normalised output from -1 to 1 // get normalised output from -1 to 1
float get_output_norm(void); float get_output_norm(void);
// a bitmask type wide enough for NUM_SERVO_CHANNELS // a bitmask type wide enough for NUM_SERVO_CHANNELS
typedef uint16_t servo_mask_t; typedef uint16_t servo_mask_t;
@ -224,7 +224,7 @@ private:
class SRV_Channels { class SRV_Channels {
public: public:
friend class SRV_Channel; friend class SRV_Channel;
// constructor // constructor
SRV_Channels(void); SRV_Channels(void);
@ -241,7 +241,7 @@ public:
// set output value for a specific function channel as a pwm value // set output value for a specific function channel as a pwm value
static void set_output_pwm_chan(uint8_t chan, uint16_t value); static void set_output_pwm_chan(uint8_t chan, uint16_t value);
// set output value for a function channel as a scaled value. This // set output value for a function channel as a scaled value. This
// calls calc_pwm() to also set the pwm value // calls calc_pwm() to also set the pwm value
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value); static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value);
@ -290,7 +290,7 @@ public:
// set and save the trim for a function channel to the output value // set and save the trim for a function channel to the output value
static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function); static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function);
// set the trim for a function channel to min of the channel // set the trim for a function channel to min of the channel
static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function); static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function);
@ -333,7 +333,7 @@ public:
// enable channels by mask // enable channels by mask
static void enable_by_mask(uint16_t mask); static void enable_by_mask(uint16_t mask);
// return the current function for a channel // return the current function for a channel
static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel); static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel);
@ -357,7 +357,7 @@ public:
// set output refresh frequency on a servo function // set output refresh frequency on a servo function
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency); static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency);
// control pass-thru of channels // control pass-thru of channels
void disable_passthrough(bool disable) { void disable_passthrough(bool disable) {
disabled_passthrough = disable; disabled_passthrough = disable;
@ -365,7 +365,7 @@ public:
// constrain to output min/max for function // constrain to output min/max for function
static void constrain_pwm(SRV_Channel::Aux_servo_function_t function); static void constrain_pwm(SRV_Channel::Aux_servo_function_t function);
// calculate PWM for all channels // calculate PWM for all channels
static void calc_pwm(void); static void calc_pwm(void);
@ -376,7 +376,7 @@ public:
// upgrade RC* parameters into SERVO* parameters // upgrade RC* parameters into SERVO* parameters
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap); static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap);
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel); static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
private: private:
struct { struct {
bool k_throttle_reversible:1; bool k_throttle_reversible:1;
@ -388,7 +388,7 @@ private:
static Bitmask function_mask; static Bitmask function_mask;
static bool initialised; static bool initialised;
// this static arrangement is to avoid having static objects in AP_Param tables // this static arrangement is to avoid having static objects in AP_Param tables
static SRV_Channel *channels; static SRV_Channel *channels;
static SRV_Channels *instance; static SRV_Channels *instance;

View File

@ -137,7 +137,7 @@ void SRV_Channels::update_aux_servo_function(void)
for (uint8_t i = 0; i < SRV_Channel::k_nr_aux_servo_functions; i++) { for (uint8_t i = 0; i < SRV_Channel::k_nr_aux_servo_functions; i++) {
functions[i].channel_mask = 0; functions[i].channel_mask = 0;
} }
// set auxiliary ranges // set auxiliary ranges
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
channels[i].aux_servo_function_setup(); channels[i].aux_servo_function_setup();
@ -147,12 +147,11 @@ void SRV_Channels::update_aux_servo_function(void)
initialised = true; initialised = true;
} }
/// Should be called after the the servo functions have been initialized /// Should be called after the the servo functions have been initialized
void SRV_Channels::enable_aux_servos() void SRV_Channels::enable_aux_servos()
{ {
hal.rcout->set_default_rate(uint16_t(instance->default_rate.get())); hal.rcout->set_default_rate(uint16_t(instance->default_rate.get()));
update_aux_servo_function(); update_aux_servo_function();
// enable all channels that are set to a valid function. This // enable all channels that are set to a valid function. This
@ -446,7 +445,6 @@ int16_t SRV_Channels::get_output_scaled(SRV_Channel::Aux_servo_function_t functi
return 0; return 0;
} }
// set the trim for a function channel to given pwm // set the trim for a function channel to given pwm
void SRV_Channels::set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm) void SRV_Channels::set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm)
{ {
@ -481,7 +479,6 @@ void SRV_Channels::set_default_function(uint8_t chan, SRV_Channel::Aux_servo_fun
} }
} }
void SRV_Channels::set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function) void SRV_Channels::set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function)
{ {
uint8_t chan; uint8_t chan;
@ -520,7 +517,6 @@ void SRV_Channels::adjust_trim(SRV_Channel::Aux_servo_function_t function, float
} }
} }
// get pwm output for the first channel of the given function type. // get pwm output for the first channel of the given function type.
bool SRV_Channels::get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value) bool SRV_Channels::get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value)
{ {
@ -650,7 +646,7 @@ bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_ch
// upgrade already done // upgrade already done
return false; return false;
} }
// old system had 14 RC channels // old system had 14 RC channels
for (uint8_t i=0; i<14; i++) { for (uint8_t i=0; i<14; i++) {
uint8_t k = rc_keys[i]; uint8_t k = rc_keys[i];
@ -679,7 +675,7 @@ bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_ch
{ 1, &srv_chan.function, nullptr, AP_PARAM_INT8, FLAG_AUX_ONLY }, { 1, &srv_chan.function, nullptr, AP_PARAM_INT8, FLAG_AUX_ONLY },
}; };
bool is_aux = aux_channel_mask & (1U<<i); bool is_aux = aux_channel_mask & (1U<<i);
for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) { for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
const struct mapping &m = mapping[j]; const struct mapping &m = mapping[j];
AP_Param::ConversionInfo info; AP_Param::ConversionInfo info;
@ -696,7 +692,7 @@ bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_ch
// if this was an aux channel we need to shift by 6 bits, but not for RCn_FUNCTION // if this was an aux channel we need to shift by 6 bits, but not for RCn_FUNCTION
info.old_group_element = (is_aux && !aux_only)?(m.old_index<<6):m.old_index; info.old_group_element = (is_aux && !aux_only)?(m.old_index<<6):m.old_index;
if (!AP_Param::find_old_parameter(&info, v)) { if (!AP_Param::find_old_parameter(&info, v)) {
// the parameter wasn't set in the old eeprom // the parameter wasn't set in the old eeprom
continue; continue;
@ -706,7 +702,7 @@ bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_ch
// special mapping from RCn_REV to RCn_REVERSED // special mapping from RCn_REV to RCn_REVERSED
v8.set(v8.get() == -1?1:0); v8.set(v8.get() == -1?1:0);
} }
if (!m.new_srv_param->configured_in_storage()) { if (!m.new_srv_param->configured_in_storage()) {
// not configured yet in new eeprom // not configured yet in new eeprom
if (m.type == AP_PARAM_INT16) { if (m.type == AP_PARAM_INT16) {
@ -741,15 +737,12 @@ bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_ch
} }
} }
// mark the upgrade as having been done // mark the upgrade as having been done
channels[15].function.set_and_save(channels[15].function.get()); channels[15].function.set_and_save(channels[15].function.get());
return true; return true;
} }
/* /*
Upgrade servo MIN/MAX/TRIM/REVERSE parameters for a single AP_Motors Upgrade servo MIN/MAX/TRIM/REVERSE parameters for a single AP_Motors
RC_Channel servo from previous firmwares, setting the equivalent RC_Channel servo from previous firmwares, setting the equivalent
@ -773,7 +766,7 @@ void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors
{ 2, &srv_chan.servo_max, AP_PARAM_INT16, FLAG_NONE }, { 2, &srv_chan.servo_max, AP_PARAM_INT16, FLAG_NONE },
{ 3, &srv_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE }, { 3, &srv_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE },
}; };
for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) { for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
const struct mapping &m = mapping[j]; const struct mapping &m = mapping[j];
AP_Param::ConversionInfo info; AP_Param::ConversionInfo info;
@ -785,7 +778,7 @@ void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors
info.type = m.type; info.type = m.type;
info.new_name = nullptr; info.new_name = nullptr;
info.old_group_element = ap_motors_idx | (m.old_index<<6); info.old_group_element = ap_motors_idx | (m.old_index<<6);
if (!AP_Param::find_old_parameter(&info, v)) { if (!AP_Param::find_old_parameter(&info, v)) {
// the parameter wasn't set in the old eeprom // the parameter wasn't set in the old eeprom
continue; continue;
@ -807,7 +800,6 @@ void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors
} }
} }
// set RC output frequency on a function output // set RC output frequency on a function output
void SRV_Channels::set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency_hz) void SRV_Channels::set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency_hz)
{ {

View File

@ -95,7 +95,7 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
// @Group: 16_ // @Group: 16_
// @Path: SRV_Channel.cpp // @Path: SRV_Channel.cpp
AP_SUBGROUPINFO(obj_channels[15], "16_", 16, SRV_Channels, SRV_Channel), AP_SUBGROUPINFO(obj_channels[15], "16_", 16, SRV_Channels, SRV_Channel),
// @Param: _AUTO_TRIM // @Param: _AUTO_TRIM
// @DisplayName: Automatic servo trim // @DisplayName: Automatic servo trim
// @Description: This enables automatic servo trim in flight. Servos will be trimed in stabilized flight modes when the aircraft is close to level. Changes to servo trim will be saved every 10 seconds and will persist between flights. // @Description: This enables automatic servo trim in flight. Servos will be trimed in stabilized flight modes when the aircraft is close to level. Changes to servo trim will be saved every 10 seconds and will persist between flights.
@ -110,7 +110,7 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
// @User: Advanced // @User: Advanced
// @Units: Hz // @Units: Hz
AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50), AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
AP_GROUPEND AP_GROUPEND
}; };
@ -121,7 +121,7 @@ SRV_Channels::SRV_Channels(void)
{ {
instance = this; instance = this;
channels = obj_channels; channels = obj_channels;
// set defaults from the parameter table // set defaults from the parameter table
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);