ArduCopter: Fix up after refactoring RC_Channel class

Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to  get and set functionsss

old public member(int16_t)   get function -> int16_t     set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in                     c.get_radio_in()           c.set_radio_in(v)
c.control_in                   c.get_control_in()         c.set_control_in(v)
c.servo_out                    c.get_servo_out()          c.set_servo_out(v)
c.pwm_out                      c.get_pwm_out()            // use existing
c.radio_out                    c.get_radio_out()          c.set_radio_out(v)
c.radio_max                    c.get_radio_max()          c.set_radio_max(v)
c.radio_min                    c.get_radio_min()          c.set_radio_min(v)
c.radio_trim                   c.get_radio_trim()         c.set_radio_trim(v);

c.min_max_configured() // return true if min and max are configured

Because data members of RC_Channels are now private and so cannot be written directly
 some overloads are provided in the Plane classes to provide the old functionality

new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);

new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;

Rename functions

 RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
    to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)

 RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
    to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)

 Rationale:

        RC_Channel is a complicated class, which combines
        several functionalities dealing with stick inputs
        in pwm and logical units, logical and actual actuator
        outputs, unit conversion etc, etc
        The intent of this PR is to clarify existing use of
        the class. At the basic level it should now be possible
        to grep all places where private variable is set by
        searching for the set_xx function.

        (The wider purpose is to provide a more generic and
        logically simpler method of output mixing. This is a small step)
This commit is contained in:
skyscraper 2016-05-08 09:46:59 +01:00 committed by Andrew Tridgell
parent 7f29903287
commit 6f200fa923
28 changed files with 168 additions and 166 deletions

View File

@ -475,7 +475,7 @@ void Copter::one_hz_loop()
motors.set_frame_orientation(g.frame_orientation); motors.set_frame_orientation(g.frame_orientation);
// set all throttle channel settings // set all throttle channel settings
motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max); motors.set_throttle_range(g.throttle_min, channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
// set hover throttle // set hover throttle
motors.set_hover_throttle(g.throttle_mid); motors.set_hover_throttle(g.throttle_mid);
#endif #endif
@ -566,17 +566,17 @@ void Copter::update_simple_mode(void)
if (ap.simple_mode == 1) { if (ap.simple_mode == 1) {
// rotate roll, pitch input by -initial simple heading (i.e. north facing) // rotate roll, pitch input by -initial simple heading (i.e. north facing)
rollx = channel_roll->control_in*simple_cos_yaw - channel_pitch->control_in*simple_sin_yaw; rollx = channel_roll->get_control_in()*simple_cos_yaw - channel_pitch->get_control_in()*simple_sin_yaw;
pitchx = channel_roll->control_in*simple_sin_yaw + channel_pitch->control_in*simple_cos_yaw; pitchx = channel_roll->get_control_in()*simple_sin_yaw + channel_pitch->get_control_in()*simple_cos_yaw;
}else{ }else{
// rotate roll, pitch input by -super simple heading (reverse of heading to home) // rotate roll, pitch input by -super simple heading (reverse of heading to home)
rollx = channel_roll->control_in*super_simple_cos_yaw - channel_pitch->control_in*super_simple_sin_yaw; rollx = channel_roll->get_control_in()*super_simple_cos_yaw - channel_pitch->get_control_in()*super_simple_sin_yaw;
pitchx = channel_roll->control_in*super_simple_sin_yaw + channel_pitch->control_in*super_simple_cos_yaw; pitchx = channel_roll->get_control_in()*super_simple_sin_yaw + channel_pitch->get_control_in()*super_simple_cos_yaw;
} }
// rotate roll, pitch input from north facing to vehicle's perspective // rotate roll, pitch input from north facing to vehicle's perspective
channel_roll->control_in = rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw(); channel_roll->set_control_in(rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw());
channel_pitch->control_in = -rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw(); channel_pitch->set_control_in(-rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw());
} }
// update_super_simple_bearing - adjusts simple bearing based on location // update_super_simple_bearing - adjusts simple bearing based on location

View File

@ -293,7 +293,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// failsafe parameter checks // failsafe parameter checks
if (g.failsafe_throttle) { if (g.failsafe_throttle) {
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900 // check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
if (channel_throttle->radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) { if (channel_throttle->get_radio_min() <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
if (display_failure) { if (display_failure) {
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE"); gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
} }
@ -343,7 +343,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check throttle is above failsafe throttle // check throttle is above failsafe throttle
// this is near the bottom to allow other failures to be displayed before checking pilot throttle // this is near the bottom to allow other failures to be displayed before checking pilot throttle
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) { if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) { if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->get_radio_in() < g.failsafe_throttle_value) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe"); gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
@ -373,27 +373,27 @@ void Copter::pre_arm_rc_checks()
} }
// check if radio has been calibrated // check if radio has been calibrated
if (!channel_throttle->radio_min.configured() || !channel_throttle->radio_max.configured()) { if (!channel_throttle->min_max_configured()) {
return; return;
} }
// check channels 1 & 2 have min <= 1300 and max >= 1700 // check channels 1 & 2 have min <= 1300 and max >= 1700
if (channel_roll->radio_min > 1300 || channel_roll->radio_max < 1700 || channel_pitch->radio_min > 1300 || channel_pitch->radio_max < 1700) { if (channel_roll->get_radio_min() > 1300 || channel_roll->get_radio_max() < 1700 || channel_pitch->get_radio_min() > 1300 || channel_pitch->get_radio_max() < 1700) {
return; return;
} }
// check channels 3 & 4 have min <= 1300 and max >= 1700 // check channels 3 & 4 have min <= 1300 and max >= 1700
if (channel_throttle->radio_min > 1300 || channel_throttle->radio_max < 1700 || channel_yaw->radio_min > 1300 || channel_yaw->radio_max < 1700) { if (channel_throttle->get_radio_min() > 1300 || channel_throttle->get_radio_max() < 1700 || channel_yaw->get_radio_min() > 1300 || channel_yaw->get_radio_max() < 1700) {
return; return;
} }
// check channels 1 & 2 have trim >= 1300 and <= 1700 // check channels 1 & 2 have trim >= 1300 and <= 1700
if (channel_roll->radio_trim < 1300 || channel_roll->radio_trim > 1700 || channel_pitch->radio_trim < 1300 || channel_pitch->radio_trim > 1700) { if (channel_roll->get_radio_trim() < 1300 || channel_roll->get_radio_trim() > 1700 || channel_pitch->get_radio_trim() < 1300 || channel_pitch->get_radio_trim() > 1700) {
return; return;
} }
// check channel 4 has trim >= 1300 and <= 1700 // check channel 4 has trim >= 1300 and <= 1700
if (channel_yaw->radio_trim < 1300 || channel_yaw->radio_trim > 1700) { if (channel_yaw->get_radio_trim() < 1300 || channel_yaw->get_radio_trim() > 1700) {
return; return;
} }
@ -671,7 +671,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// check throttle // check throttle
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) { if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
// check throttle is not too low - must be above failsafe throttle // check throttle is not too low - must be above failsafe throttle
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) { if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->get_radio_in() < g.failsafe_throttle_value) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe"); gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
@ -685,7 +685,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// check throttle is not too high - skips checks if arming from GCS in Guided // check throttle is not too high - skips checks if arming from GCS in Guided
if (!(arming_from_gcs && control_mode == GUIDED)) { if (!(arming_from_gcs && control_mode == GUIDED)) {
// above top of deadband is too always high // above top of deadband is too always high
if (channel_throttle->control_in > get_takeoff_trigger_throttle()) { if (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high"); gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
@ -696,7 +696,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false; return false;
} }
// in manual modes throttle must be at zero // in manual modes throttle must be at zero
if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) { if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->get_control_in() > 0) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high"); gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");

View File

@ -67,7 +67,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// check throttle is at zero // check throttle is at zero
read_radio(); read_radio();
if (channel_throttle->control_in != 0) { if (channel_throttle->get_control_in() != 0) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero"); gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
ap.compass_mot = false; ap.compass_mot = false;
return 1; return 1;
@ -157,7 +157,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
read_radio(); read_radio();
// pass through throttle to motors // pass through throttle to motors
motors.throttle_pass_through(channel_throttle->radio_in); motors.throttle_pass_through(channel_throttle->get_radio_in());
// read some compass values // read some compass values
compass.read(); compass.read();
@ -166,7 +166,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
read_battery(); read_battery();
// calculate scaling for throttle // calculate scaling for throttle
throttle_pct = (float)channel_throttle->control_in / 1000.0f; throttle_pct = (float)channel_throttle->get_control_in() / 1000.0f;
throttle_pct = constrain_float(throttle_pct,0.0f,1.0f); throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
// if throttle is near zero, update base x,y,z values // if throttle is near zero, update base x,y,z values
@ -229,7 +229,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
if (AP_HAL::millis() - last_send_time > 500) { if (AP_HAL::millis() - last_send_time > 500) {
last_send_time = AP_HAL::millis(); last_send_time = AP_HAL::millis();
mavlink_msg_compassmot_status_send(chan, mavlink_msg_compassmot_status_send(chan,
channel_throttle->control_in, channel_throttle->get_control_in(),
battery.current_amps(), battery.current_amps(),
interference_pct[compass.get_primary()], interference_pct[compass.get_primary()],
motor_compensation[compass.get_primary()].x, motor_compensation[compass.get_primary()].x,

View File

@ -10,7 +10,7 @@
bool Copter::acro_init(bool ignore_checks) bool Copter::acro_init(bool ignore_checks)
{ {
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (get_pilot_desired_throttle(channel_throttle->control_in) > get_non_takeoff_throttle())) { if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (get_pilot_desired_throttle(channel_throttle->get_control_in()) > get_non_takeoff_throttle())) {
return false; return false;
} }
// set target altitude to zero for reporting // set target altitude to zero for reporting
@ -36,10 +36,10 @@ void Copter::acro_run()
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// convert the input to the desired body frame rate // convert the input to the desired body frame rate
get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
// get pilot's desired throttle // get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in); pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in());
// run attitude controller // run attitude controller
attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);

View File

@ -46,20 +46,20 @@ void Copter::althold_run()
// get pilot desired lean angles // get pilot desired lean angles
float target_roll, target_pitch; float target_roll, target_pitch;
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
// get pilot's desired yaw rate // get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot desired climb rate // get pilot desired climb rate
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// helicopters are held on the ground until rotor speed runup has finished // helicopters are held on the ground until rotor speed runup has finished
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()) && motors.rotor_runup_complete()); bool takeoff_triggered = (ap.land_complete && (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()) && motors.rotor_runup_complete());
#else #else
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()) && motors.spool_up_complete()); bool takeoff_triggered = (ap.land_complete && (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()) && motors.spool_up_complete());
#endif #endif
// Alt Hold State Machine Determination // Alt Hold State Machine Determination
@ -92,7 +92,7 @@ void Copter::althold_run()
#else #else
// Multicopters do not stabilize roll/pitch/yaw when motor are stopped // Multicopters do not stabilize roll/pitch/yaw when motor are stopped
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
#endif #endif
break; break;
@ -108,7 +108,7 @@ void Copter::althold_run()
// Multicopters do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle) // Multicopters do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
break; break;
case AltHold_Takeoff: case AltHold_Takeoff:
@ -144,14 +144,14 @@ void Copter::althold_run()
#endif #endif
// call attitude controller // call attitude controller
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
// set motors to spin-when-armed if throttle at zero, otherwise full range // set motors to spin-when-armed if throttle at zero, otherwise full range
if (ap.throttle_zero) { if (ap.throttle_zero) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
} else { } else {
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
} }
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
break; break;
case AltHold_Flying: case AltHold_Flying:

View File

@ -160,7 +160,7 @@ void Copter::auto_takeoff_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range
@ -234,7 +234,7 @@ void Copter::auto_wp_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -306,7 +306,7 @@ void Copter::auto_spline_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rat // get pilot's desired yaw rat
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -400,12 +400,12 @@ void Copter::auto_land_run()
update_simple_mode(); update_simple_mode();
// process pilot's roll and pitch input // process pilot's roll and pitch input
roll_control = channel_roll->control_in; roll_control = channel_roll->get_control_in();
pitch_control = channel_pitch->control_in; pitch_control = channel_pitch->get_control_in();
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range
@ -593,7 +593,7 @@ void Copter::auto_loiter_run()
// accept pilot input of yaw // accept pilot input of yaw
float target_yaw_rate = 0; float target_yaw_rate = 0;
if(!failsafe.radio) { if(!failsafe.radio) {
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range

View File

@ -271,7 +271,7 @@ void Copter::autotune_run()
if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) { if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
return; return;
} }
@ -279,13 +279,13 @@ void Copter::autotune_run()
update_simple_mode(); update_simple_mode();
// get pilot desired lean angles // get pilot desired lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
// check for pilot requested take-off - this should not actually be possible because of autotune_init() checks // check for pilot requested take-off - this should not actually be possible because of autotune_init() checks
if (ap.land_complete && target_climb_rate > 0) { if (ap.land_complete && target_climb_rate > 0) {
@ -303,8 +303,8 @@ void Copter::autotune_run()
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
} }
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
}else{ }else{
// check if pilot is overriding the controls // check if pilot is overriding the controls
if (!is_zero(target_roll) || !is_zero(target_pitch) || !is_zero(target_yaw_rate) || !is_zero(target_climb_rate)) { if (!is_zero(target_roll) || !is_zero(target_pitch) || !is_zero(target_yaw_rate) || !is_zero(target_climb_rate)) {

View File

@ -60,13 +60,13 @@ void Copter::circle_run()
// process pilot inputs // process pilot inputs
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
circle_pilot_yaw_override = true; circle_pilot_yaw_override = true;
} }
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
// check for pilot requested take-off // check for pilot requested take-off
if (ap.land_complete && target_climb_rate > 0) { if (ap.land_complete && target_climb_rate > 0) {

View File

@ -56,10 +56,10 @@ void Copter::drift_run()
} }
// convert pilot input to lean angles // convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// get pilot's desired throttle // get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in); pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in());
// Grab inertial velocity // Grab inertial velocity
const Vector3f& vel = inertial_nav.get_velocity(); const Vector3f& vel = inertial_nav.get_velocity();
@ -75,7 +75,7 @@ void Copter::drift_run()
roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT); roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT); pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
roll_input = roll_input * .96f + (float)channel_yaw->control_in * .04f; roll_input = roll_input * .96f + (float)channel_yaw->get_control_in() * .04f;
//convert user input into desired roll velocity //convert user input into desired roll velocity
float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN); float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);

View File

@ -53,7 +53,7 @@ bool Copter::flip_init(bool ignore_checks)
} }
// ensure roll input is less than 40deg // ensure roll input is less than 40deg
if (abs(channel_roll->control_in) >= 4000) { if (abs(channel_roll->get_control_in()) >= 4000) {
return false; return false;
} }
@ -73,11 +73,11 @@ bool Copter::flip_init(bool ignore_checks)
flip_roll_dir = flip_pitch_dir = 0; flip_roll_dir = flip_pitch_dir = 0;
// choose direction based on pilot's roll and pitch sticks // choose direction based on pilot's roll and pitch sticks
if (channel_pitch->control_in > 300) { if (channel_pitch->get_control_in() > 300) {
flip_pitch_dir = FLIP_PITCH_BACK; flip_pitch_dir = FLIP_PITCH_BACK;
}else if(channel_pitch->control_in < -300) { }else if(channel_pitch->get_control_in() < -300) {
flip_pitch_dir = FLIP_PITCH_FORWARD; flip_pitch_dir = FLIP_PITCH_FORWARD;
}else if (channel_roll->control_in >= 0) { }else if (channel_roll->get_control_in() >= 0) {
flip_roll_dir = FLIP_ROLL_RIGHT; flip_roll_dir = FLIP_ROLL_RIGHT;
}else{ }else{
flip_roll_dir = FLIP_ROLL_LEFT; flip_roll_dir = FLIP_ROLL_LEFT;
@ -102,12 +102,12 @@ void Copter::flip_run()
float recovery_angle; float recovery_angle;
// if pilot inputs roll > 40deg or timeout occurs abandon flip // if pilot inputs roll > 40deg or timeout occurs abandon flip
if (!motors.armed() || (abs(channel_roll->control_in) >= 4000) || (abs(channel_pitch->control_in) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) { if (!motors.armed() || (abs(channel_roll->get_control_in()) >= 4000) || (abs(channel_pitch->get_control_in()) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) {
flip_state = Flip_Abandon; flip_state = Flip_Abandon;
} }
// get pilot's desired throttle // get pilot's desired throttle
throttle_out = get_pilot_desired_throttle(channel_throttle->control_in); throttle_out = get_pilot_desired_throttle(channel_throttle->get_control_in());
// get corrected angle based on direction and axis of rotation // get corrected angle based on direction and axis of rotation
// we flip the sign of flip_angle to minimize the code repetition // we flip the sign of flip_angle to minimize the code repetition

View File

@ -314,7 +314,7 @@ void Copter::guided_takeoff_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range
@ -352,7 +352,7 @@ void Copter::guided_pos_control_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -401,7 +401,7 @@ void Copter::guided_vel_control_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -455,7 +455,7 @@ void Copter::guided_posvel_control_run()
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }

View File

@ -102,8 +102,8 @@ void Copter::land_gps_run()
update_simple_mode(); update_simple_mode();
// process pilot's roll and pitch input // process pilot's roll and pitch input
roll_control = channel_roll->control_in; roll_control = channel_roll->get_control_in();
pitch_control = channel_pitch->control_in; pitch_control = channel_pitch->get_control_in();
// record if pilot has overriden roll or pitch // record if pilot has overriden roll or pitch
if (roll_control != 0 || pitch_control != 0) { if (roll_control != 0 || pitch_control != 0) {
@ -112,7 +112,7 @@ void Copter::land_gps_run()
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range
@ -172,11 +172,11 @@ void Copter::land_nogps_run()
update_simple_mode(); update_simple_mode();
// get pilot desired lean angles // get pilot desired lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately

View File

@ -54,13 +54,13 @@ void Copter::loiter_run()
update_simple_mode(); update_simple_mode();
// process pilot's roll and pitch input // process pilot's roll and pitch input
wp_nav.set_pilot_desired_acceleration(channel_roll->control_in, channel_pitch->control_in); wp_nav.set_pilot_desired_acceleration(channel_roll->get_control_in(), channel_pitch->get_control_in());
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
} else { } else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason // clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
@ -77,7 +77,7 @@ void Copter::loiter_run()
loiter_state = Loiter_MotorStopped; loiter_state = Loiter_MotorStopped;
} else if (!ap.auto_armed) { } else if (!ap.auto_armed) {
loiter_state = Loiter_NotAutoArmed; loiter_state = Loiter_NotAutoArmed;
} else if (takeoff_state.running || (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()))){ } else if (takeoff_state.running || (ap.land_complete && (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()))){
loiter_state = Loiter_Takeoff; loiter_state = Loiter_Takeoff;
} else if (ap.land_complete){ } else if (ap.land_complete){
loiter_state = Loiter_Landed; loiter_state = Loiter_Landed;
@ -106,7 +106,7 @@ void Copter::loiter_run()
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
// multicopters do not stabilize roll/pitch/yaw when motors are stopped // multicopters do not stabilize roll/pitch/yaw when motors are stopped
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
#endif #endif
break; break;
@ -122,7 +122,7 @@ void Copter::loiter_run()
// Multicopters do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle) // Multicopters do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
break; break;
case Loiter_Takeoff: case Loiter_Takeoff:
@ -159,14 +159,14 @@ void Copter::loiter_run()
// call attitude controller // call attitude controller
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
// if throttle zero reset attitude and exit immediately // if throttle zero reset attitude and exit immediately
if (ap.throttle_zero) { if (ap.throttle_zero) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
} else { } else {
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
} }
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
break; break;
case Loiter_Flying: case Loiter_Flying:

View File

@ -145,7 +145,7 @@ void Copter::poshold_run()
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
return; return;
} }
@ -155,17 +155,17 @@ void Copter::poshold_run()
update_simple_mode(); update_simple_mode();
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot desired climb rate (for alt-hold mode and take-off) // get pilot desired climb rate (for alt-hold mode and take-off)
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
// get takeoff adjusted pilot and takeoff climb rates // get takeoff adjusted pilot and takeoff climb rates
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate); takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || channel_throttle->control_in > get_takeoff_trigger_throttle())) { if (ap.land_complete && (takeoff_state.running || channel_throttle->get_control_in() > get_takeoff_trigger_throttle())) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
@ -192,12 +192,12 @@ void Copter::poshold_run()
} }
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
return; return;
}else{ }else{
// convert pilot input to lean angles // convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// convert inertial nav earth-frame velocities to body-frame // convert inertial nav earth-frame velocities to body-frame
// To-Do: move this to AP_Math (or perhaps we already have a function to do this) // To-Do: move this to AP_Math (or perhaps we already have a function to do this)

View File

@ -153,7 +153,7 @@ void Copter::rtl_climb_return_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -220,7 +220,7 @@ void Copter::rtl_loiterathome_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD); set_auto_yaw_mode(AUTO_YAW_HOLD);
} }
@ -312,12 +312,12 @@ void Copter::rtl_descent_run()
update_simple_mode(); update_simple_mode();
// process pilot's roll and pitch input // process pilot's roll and pitch input
roll_control = channel_roll->control_in; roll_control = channel_roll->get_control_in();
pitch_control = channel_pitch->control_in; pitch_control = channel_pitch->get_control_in();
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range
@ -413,12 +413,12 @@ void Copter::rtl_land_run()
update_simple_mode(); update_simple_mode();
// process pilot's roll and pitch input // process pilot's roll and pitch input
roll_control = channel_roll->control_in; roll_control = channel_roll->get_control_in();
pitch_control = channel_pitch->control_in; pitch_control = channel_pitch->get_control_in();
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// set motors to full range // set motors to full range

View File

@ -36,7 +36,7 @@ void Copter::sport_run()
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) { if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
return; return;
} }
@ -46,8 +46,8 @@ void Copter::sport_run()
// get pilot's desired roll and pitch rates // get pilot's desired roll and pitch rates
// calculate rate requests // calculate rate requests
target_roll_rate = channel_roll->control_in * g.acro_rp_p; target_roll_rate = channel_roll->get_control_in() * g.acro_rp_p;
target_pitch_rate = channel_pitch->control_in * g.acro_rp_p; target_pitch_rate = channel_pitch->get_control_in() * g.acro_rp_p;
int32_t roll_angle = wrap_180_cd(ahrs.roll_sensor); int32_t roll_angle = wrap_180_cd(ahrs.roll_sensor);
target_roll_rate -= constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll; target_roll_rate -= constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll;
@ -69,17 +69,17 @@ void Copter::sport_run()
} }
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in); target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
// get takeoff adjusted pilot and takeoff climb rates // get takeoff adjusted pilot and takeoff climb rates
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate); takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || (channel_throttle->control_in > get_takeoff_trigger_throttle()))) { if (ap.land_complete && (takeoff_state.running || (channel_throttle->get_control_in() > get_takeoff_trigger_throttle()))) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
@ -98,8 +98,8 @@ void Copter::sport_run()
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
} }
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-throttle_average);
}else{ }else{
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);

View File

@ -10,7 +10,7 @@
bool Copter::stabilize_init(bool ignore_checks) bool Copter::stabilize_init(bool ignore_checks)
{ {
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (get_pilot_desired_throttle(channel_throttle->control_in) > get_non_takeoff_throttle())) { if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (get_pilot_desired_throttle(channel_throttle->get_control_in()) > get_non_takeoff_throttle())) {
return false; return false;
} }
// set target altitude to zero for reporting // set target altitude to zero for reporting
@ -41,13 +41,13 @@ void Copter::stabilize_run()
// convert pilot input to lean angles // convert pilot input to lean angles
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats // To-Do: convert get_pilot_desired_lean_angles to return angles as floats
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot's desired throttle // get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in); pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in());
// call attitude controller // call attitude controller
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());

View File

@ -35,7 +35,7 @@ void Copter::esc_calibration_startup_check()
switch (g.esc_calibrate) { switch (g.esc_calibrate) {
case ESCCAL_NONE: case ESCCAL_NONE:
// check if throttle is high // check if throttle is high
if (channel_throttle->control_in >= ESC_CALIBRATION_HIGH_THROTTLE) { if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
// we will enter esc_calibrate mode on next reboot // we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH); g.esc_calibrate.set_and_save(ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
// send message to gcs // send message to gcs
@ -48,7 +48,7 @@ void Copter::esc_calibration_startup_check()
break; break;
case ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH: case ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:
// check if throttle is high // check if throttle is high
if (channel_throttle->control_in >= ESC_CALIBRATION_HIGH_THROTTLE) { if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
// pass through pilot throttle to escs // pass through pilot throttle to escs
esc_calibration_passthrough(); esc_calibration_passthrough();
} }
@ -100,7 +100,7 @@ void Copter::esc_calibration_passthrough()
delay(10); delay(10);
// pass through to motors // pass through to motors
motors.throttle_pass_through(channel_throttle->radio_in); motors.throttle_pass_through(channel_throttle->get_radio_in());
} }
#endif // FRAME_CONFIG != HELI_FRAME #endif // FRAME_CONFIG != HELI_FRAME
} }
@ -126,7 +126,7 @@ void Copter::esc_calibration_auto()
// raise throttle to maximum // raise throttle to maximum
delay(10); delay(10);
motors.throttle_pass_through(channel_throttle->radio_max); motors.throttle_pass_through(channel_throttle->get_radio_max());
// wait for safety switch to be pressed // wait for safety switch to be pressed
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
@ -141,7 +141,7 @@ void Copter::esc_calibration_auto()
delay(5000); delay(5000);
// reduce throttle to minimum // reduce throttle to minimum
motors.throttle_pass_through(channel_throttle->radio_min); motors.throttle_pass_through(channel_throttle->get_radio_min());
// clear esc parameter // clear esc parameter
g.esc_calibrate.set_and_save(ESCCAL_NONE); g.esc_calibrate.set_and_save(ESCCAL_NONE);

View File

@ -255,7 +255,7 @@ void Copter::exit_mode(control_mode_t old_control_mode, control_mode_t new_contr
// smooth throttle transition when switching from manual to automatic flight modes // smooth throttle transition when switching from manual to automatic flight modes
if (mode_has_manual_throttle(old_control_mode) && !mode_has_manual_throttle(new_control_mode) && motors.armed() && !ap.land_complete) { if (mode_has_manual_throttle(old_control_mode) && !mode_has_manual_throttle(new_control_mode) && motors.armed() && !ap.land_complete) {
// this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle // this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle
set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(channel_throttle->control_in)); set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(channel_throttle->get_control_in()));
} }
// cancel any takeoffs in progress // cancel any takeoffs in progress

View File

@ -49,7 +49,7 @@ void Copter::heli_acro_run()
if (!motors.has_flybar()){ if (!motors.has_flybar()){
// convert the input to the desired body frame rate // convert the input to the desired body frame rate
get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
if (motors.supports_yaw_passthrough()) { if (motors.supports_yaw_passthrough()) {
// if the tail on a flybar heli has an external gyro then // if the tail on a flybar heli has an external gyro then
@ -78,7 +78,7 @@ void Copter::heli_acro_run()
// if there is no external gyro then run the usual // if there is no external gyro then run the usual
// ACRO_YAW_P gain on the input control, including // ACRO_YAW_P gain on the input control, including
// deadzone // deadzone
yaw_in = get_pilot_desired_yaw_rate(channel_yaw->control_in); yaw_in = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
} }
// run attitude controller // run attitude controller
@ -86,7 +86,7 @@ void Copter::heli_acro_run()
} }
// get pilot's desired throttle // get pilot's desired throttle
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->control_in); pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
// output pilot's throttle without angle boost // output pilot's throttle without angle boost
attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);

View File

@ -51,13 +51,13 @@ void Copter::heli_stabilize_run()
// convert pilot input to lean angles // convert pilot input to lean angles
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats // To-Do: convert get_pilot_desired_lean_angles to return angles as floats
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max); get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
// get pilot's desired throttle // get pilot's desired throttle
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->control_in); pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
// call attitude controller // call attitude controller
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());

View File

@ -122,7 +122,7 @@ void Copter::update_throttle_thr_mix()
if (mode_has_manual_throttle(control_mode)) { if (mode_has_manual_throttle(control_mode)) {
// manual throttle // manual throttle
if(channel_throttle->control_in <= 0) { if(channel_throttle->get_control_in() <= 0) {
motors.set_throttle_mix_min(); motors.set_throttle_mix_min();
} else { } else {
motors.set_throttle_mix_mid(); motors.set_throttle_mix_mid();

View File

@ -39,7 +39,9 @@ void Copter::motor_test_output()
case MOTOR_TEST_THROTTLE_PERCENT: case MOTOR_TEST_THROTTLE_PERCENT:
// sanity check motor_test_throttle value // sanity check motor_test_throttle value
if (motor_test_throttle_value <= 100) { if (motor_test_throttle_value <= 100) {
pwm = channel_throttle->radio_min + (channel_throttle->radio_max - channel_throttle->radio_min) * (float)motor_test_throttle_value/100.0f; pwm = channel_throttle->get_radio_min()
+ (channel_throttle->get_radio_max() - channel_throttle->get_radio_min())
* (float)motor_test_throttle_value/100.0f;
} }
break; break;
@ -48,7 +50,7 @@ void Copter::motor_test_output()
break; break;
case MOTOR_TEST_THROTTLE_PILOT: case MOTOR_TEST_THROTTLE_PILOT:
pwm = channel_throttle->radio_in; pwm = channel_throttle->get_radio_in();
break; break;
default: default:

View File

@ -16,12 +16,12 @@ void Copter::arm_motors_check()
static int16_t arming_counter; static int16_t arming_counter;
// ensure throttle is down // ensure throttle is down
if (channel_throttle->control_in > 0) { if (channel_throttle->get_control_in() > 0) {
arming_counter = 0; arming_counter = 0;
return; return;
} }
int16_t tmp = channel_yaw->control_in; int16_t tmp = channel_yaw->get_control_in();
// full right // full right
if (tmp > 4000) { if (tmp > 4000) {
@ -104,7 +104,7 @@ void Copter::auto_disarm_check()
thr_low = ap.throttle_zero; thr_low = ap.throttle_zero;
} else { } else {
float deadband_top = g.rc_3.get_control_mid() + g.throttle_deadzone; float deadband_top = g.rc_3.get_control_mid() + g.throttle_deadzone;
thr_low = g.rc_3.control_in <= deadband_top; thr_low = g.rc_3.get_control_in() <= deadband_top;
} }
if (!thr_low || !ap.land_complete) { if (!thr_low || !ap.land_complete) {
@ -288,7 +288,7 @@ void Copter::lost_vehicle_check()
} }
// ensure throttle is down, motors not armed, pitch and roll rc at max. Note: rc1=roll rc2=pitch // ensure throttle is down, motors not armed, pitch and roll rc at max. Note: rc1=roll rc2=pitch
if (ap.throttle_zero && !motors.armed() && (channel_roll->control_in > 4000) && (channel_pitch->control_in > 4000)) { if (ap.throttle_zero && !motors.armed() && (channel_roll->get_control_in() > 4000) && (channel_pitch->get_control_in() > 4000)) {
if (soundalarm_counter >= LOST_VEHICLE_DELAY) { if (soundalarm_counter >= LOST_VEHICLE_DELAY) {
if (AP_Notify::flags.vehicle_lost == false) { if (AP_Notify::flags.vehicle_lost == false) {
AP_Notify::flags.vehicle_lost = true; AP_Notify::flags.vehicle_lost = true;

View File

@ -58,7 +58,7 @@ void Copter::init_rc_out()
motors.set_frame_orientation(g.frame_orientation); motors.set_frame_orientation(g.frame_orientation);
motors.Init(); // motor initialisation motors.Init(); // motor initialisation
#if FRAME_CONFIG != HELI_FRAME #if FRAME_CONFIG != HELI_FRAME
motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max); motors.set_throttle_range(g.throttle_min, channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
motors.set_hover_throttle(g.throttle_mid); motors.set_hover_throttle(g.throttle_mid);
#endif #endif
@ -84,7 +84,7 @@ void Copter::init_rc_out()
// setup correct scaling for ESCs like the UAVCAN PX4ESC which // setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed. // take a proportion of speed.
hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max); hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
} }
// enable_motor_output() - enable and output lowest possible value to motors // enable_motor_output() - enable and output lowest possible value to motors
@ -104,8 +104,8 @@ void Copter::read_radio()
ap.new_radio_frame = true; ap.new_radio_frame = true;
RC_Channel::set_pwm_all(); RC_Channel::set_pwm_all();
set_throttle_and_failsafe(channel_throttle->radio_in); set_throttle_and_failsafe(channel_throttle->get_radio_in());
set_throttle_zero_flag(channel_throttle->control_in); set_throttle_zero_flag(channel_throttle->get_control_in());
// flag we must have an rc receiver attached // flag we must have an rc receiver attached
if (!failsafe.rc_override_active) { if (!failsafe.rc_override_active) {
@ -119,7 +119,7 @@ void Copter::read_radio()
radio_passthrough_to_motors(); radio_passthrough_to_motors();
float dt = (tnow_ms - last_update_ms)*1.0e-3f; float dt = (tnow_ms - last_update_ms)*1.0e-3f;
rc_throttle_control_in_filter.apply(g.rc_3.control_in, dt); rc_throttle_control_in_filter.apply(g.rc_3.get_control_in(), dt);
last_update_ms = tnow_ms; last_update_ms = tnow_ms;
}else{ }else{
uint32_t elapsed = tnow_ms - last_update_ms; uint32_t elapsed = tnow_ms - last_update_ms;
@ -198,5 +198,5 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control)
// pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters) // pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
void Copter::radio_passthrough_to_motors() void Copter::radio_passthrough_to_motors()
{ {
motors.set_radio_passthrough(channel_roll->control_in/1000.0f, channel_pitch->control_in/1000.0f, channel_throttle->control_in/1000.0f, channel_yaw->control_in/1000.0f); motors.set_radio_passthrough(channel_roll->get_control_in()/1000.0f, channel_pitch->get_control_in()/1000.0f, channel_throttle->get_control_in()/1000.0f, channel_yaw->get_control_in()/1000.0f);
} }

View File

@ -382,14 +382,14 @@ void Copter::report_optflow()
void Copter::print_radio_values() void Copter::print_radio_values()
{ {
cliSerial->printf("CH1: %d | %d\n", (int)channel_roll->radio_min, (int)channel_roll->radio_max); cliSerial->printf("CH1: %d | %d\n", (int)channel_roll->get_radio_min(), (int)channel_roll->get_radio_max());
cliSerial->printf("CH2: %d | %d\n", (int)channel_pitch->radio_min, (int)channel_pitch->radio_max); cliSerial->printf("CH2: %d | %d\n", (int)channel_pitch->get_radio_min(), (int)channel_pitch->get_radio_max());
cliSerial->printf("CH3: %d | %d\n", (int)channel_throttle->radio_min, (int)channel_throttle->radio_max); cliSerial->printf("CH3: %d | %d\n", (int)channel_throttle->get_radio_min(), (int)channel_throttle->get_radio_max());
cliSerial->printf("CH4: %d | %d\n", (int)channel_yaw->radio_min, (int)channel_yaw->radio_max); cliSerial->printf("CH4: %d | %d\n", (int)channel_yaw->get_radio_min(), (int)channel_yaw->get_radio_max());
cliSerial->printf("CH5: %d | %d\n", (int)g.rc_5.radio_min, (int)g.rc_5.radio_max); cliSerial->printf("CH5: %d | %d\n", (int)g.rc_5.get_radio_min(), (int)g.rc_5.get_radio_max());
cliSerial->printf("CH6: %d | %d\n", (int)g.rc_6.radio_min, (int)g.rc_6.radio_max); cliSerial->printf("CH6: %d | %d\n", (int)g.rc_6.get_radio_min(), (int)g.rc_6.get_radio_max());
cliSerial->printf("CH7: %d | %d\n", (int)g.rc_7.radio_min, (int)g.rc_7.radio_max); cliSerial->printf("CH7: %d | %d\n", (int)g.rc_7.get_radio_min(), (int)g.rc_7.get_radio_max());
cliSerial->printf("CH8: %d | %d\n", (int)g.rc_8.radio_min, (int)g.rc_8.radio_max); cliSerial->printf("CH8: %d | %d\n", (int)g.rc_8.get_radio_min(), (int)g.rc_8.get_radio_max());
} }
void Copter::print_switch(uint8_t p, uint8_t m, bool b) void Copter::print_switch(uint8_t p, uint8_t m, bool b)

View File

@ -24,11 +24,11 @@ void Copter::read_control_switch()
// calculate position of flight mode switch // calculate position of flight mode switch
int8_t switch_position; int8_t switch_position;
if (g.rc_5.radio_in < 1231) switch_position = 0; if (g.rc_5.get_radio_in() < 1231) switch_position = 0;
else if (g.rc_5.radio_in < 1361) switch_position = 1; else if (g.rc_5.get_radio_in() < 1361) switch_position = 1;
else if (g.rc_5.radio_in < 1491) switch_position = 2; else if (g.rc_5.get_radio_in() < 1491) switch_position = 2;
else if (g.rc_5.radio_in < 1621) switch_position = 3; else if (g.rc_5.get_radio_in() < 1621) switch_position = 3;
else if (g.rc_5.radio_in < 1750) switch_position = 4; else if (g.rc_5.get_radio_in() < 1750) switch_position = 4;
else switch_position = 5; else switch_position = 5;
// store time that switch last moved // store time that switch last moved
@ -130,7 +130,7 @@ void Copter::read_aux_switches()
} }
// check if ch7 switch has changed position // check if ch7 switch has changed position
switch_position = read_3pos_switch(g.rc_7.radio_in); switch_position = read_3pos_switch(g.rc_7.get_radio_in());
if (aux_con.CH7_flag != switch_position) { if (aux_con.CH7_flag != switch_position) {
// set the CH7 flag // set the CH7 flag
aux_con.CH7_flag = switch_position; aux_con.CH7_flag = switch_position;
@ -140,7 +140,7 @@ void Copter::read_aux_switches()
} }
// check if Ch8 switch has changed position // check if Ch8 switch has changed position
switch_position = read_3pos_switch(g.rc_8.radio_in); switch_position = read_3pos_switch(g.rc_8.get_radio_in());
if (aux_con.CH8_flag != switch_position) { if (aux_con.CH8_flag != switch_position) {
// set the CH8 flag // set the CH8 flag
aux_con.CH8_flag = switch_position; aux_con.CH8_flag = switch_position;
@ -150,7 +150,7 @@ void Copter::read_aux_switches()
} }
// check if Ch9 switch has changed position // check if Ch9 switch has changed position
switch_position = read_3pos_switch(g.rc_9.radio_in); switch_position = read_3pos_switch(g.rc_9.get_radio_in());
if (aux_con.CH9_flag != switch_position) { if (aux_con.CH9_flag != switch_position) {
// set the CH9 flag // set the CH9 flag
aux_con.CH9_flag = switch_position; aux_con.CH9_flag = switch_position;
@ -160,7 +160,7 @@ void Copter::read_aux_switches()
} }
// check if Ch10 switch has changed position // check if Ch10 switch has changed position
switch_position = read_3pos_switch(g.rc_10.radio_in); switch_position = read_3pos_switch(g.rc_10.get_radio_in());
if (aux_con.CH10_flag != switch_position) { if (aux_con.CH10_flag != switch_position) {
// set the CH10 flag // set the CH10 flag
aux_con.CH10_flag = switch_position; aux_con.CH10_flag = switch_position;
@ -170,7 +170,7 @@ void Copter::read_aux_switches()
} }
// check if Ch11 switch has changed position // check if Ch11 switch has changed position
switch_position = read_3pos_switch(g.rc_11.radio_in); switch_position = read_3pos_switch(g.rc_11.get_radio_in());
if (aux_con.CH11_flag != switch_position) { if (aux_con.CH11_flag != switch_position) {
// set the CH11 flag // set the CH11 flag
aux_con.CH11_flag = switch_position; aux_con.CH11_flag = switch_position;
@ -181,7 +181,7 @@ void Copter::read_aux_switches()
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// check if Ch12 switch has changed position // check if Ch12 switch has changed position
switch_position = read_3pos_switch(g.rc_12.radio_in); switch_position = read_3pos_switch(g.rc_12.get_radio_in());
if (aux_con.CH12_flag != switch_position) { if (aux_con.CH12_flag != switch_position) {
// set the CH12 flag // set the CH12 flag
aux_con.CH12_flag = switch_position; aux_con.CH12_flag = switch_position;
@ -196,14 +196,14 @@ void Copter::read_aux_switches()
void Copter::init_aux_switches() void Copter::init_aux_switches()
{ {
// set the CH7 ~ CH12 flags // set the CH7 ~ CH12 flags
aux_con.CH7_flag = read_3pos_switch(g.rc_7.radio_in); aux_con.CH7_flag = read_3pos_switch(g.rc_7.get_radio_in());
aux_con.CH8_flag = read_3pos_switch(g.rc_8.radio_in); aux_con.CH8_flag = read_3pos_switch(g.rc_8.get_radio_in());
aux_con.CH10_flag = read_3pos_switch(g.rc_10.radio_in); aux_con.CH10_flag = read_3pos_switch(g.rc_10.get_radio_in());
aux_con.CH11_flag = read_3pos_switch(g.rc_11.radio_in); aux_con.CH11_flag = read_3pos_switch(g.rc_11.get_radio_in());
// ch9, ch12 only supported on some boards // ch9, ch12 only supported on some boards
aux_con.CH9_flag = read_3pos_switch(g.rc_9.radio_in); aux_con.CH9_flag = read_3pos_switch(g.rc_9.get_radio_in());
aux_con.CH12_flag = read_3pos_switch(g.rc_12.radio_in); aux_con.CH12_flag = read_3pos_switch(g.rc_12.get_radio_in());
// initialise functions assigned to switches // initialise functions assigned to switches
init_aux_switch_function(g.ch7_option, aux_con.CH7_flag); init_aux_switch_function(g.ch7_option, aux_con.CH7_flag);
@ -278,7 +278,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break; break;
case AUXSW_SAVE_TRIM: case AUXSW_SAVE_TRIM:
if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (channel_throttle->control_in == 0)) { if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (channel_throttle->get_control_in() == 0)) {
save_trim(); save_trim();
} }
break; break;
@ -293,7 +293,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
} }
// do not allow saving the first waypoint with zero throttle // do not allow saving the first waypoint with zero throttle
if((mission.num_commands() == 0) && (channel_throttle->control_in == 0)){ if((mission.num_commands() == 0) && (channel_throttle->get_control_in() == 0)){
return; return;
} }
@ -322,7 +322,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
cmd.content.location = current_loc; cmd.content.location = current_loc;
// if throttle is above zero, create waypoint command // if throttle is above zero, create waypoint command
if(channel_throttle->control_in > 0) { if(channel_throttle->get_control_in() > 0) {
cmd.id = MAV_CMD_NAV_WAYPOINT; cmd.id = MAV_CMD_NAV_WAYPOINT;
}else{ }else{
// with zero throttle, create LAND command // with zero throttle, create LAND command
@ -608,8 +608,8 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
void Copter::save_trim() void Copter::save_trim()
{ {
// save roll and pitch trim // save roll and pitch trim
float roll_trim = ToRad((float)channel_roll->control_in/100.0f); float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
float pitch_trim = ToRad((float)channel_pitch->control_in/100.0f); float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
ahrs.add_trim(roll_trim, pitch_trim); ahrs.add_trim(roll_trim, pitch_trim);
Log_Write_Event(DATA_SAVE_TRIM); Log_Write_Event(DATA_SAVE_TRIM);
gcs_send_text(MAV_SEVERITY_INFO, "Trim saved"); gcs_send_text(MAV_SEVERITY_INFO, "Trim saved");
@ -626,10 +626,10 @@ void Copter::auto_trim()
AP_Notify::flags.save_trim = true; AP_Notify::flags.save_trim = true;
// calculate roll trim adjustment // calculate roll trim adjustment
float roll_trim_adjustment = ToRad((float)channel_roll->control_in / 4000.0f); float roll_trim_adjustment = ToRad((float)channel_roll->get_control_in() / 4000.0f);
// calculate pitch trim adjustment // calculate pitch trim adjustment
float pitch_trim_adjustment = ToRad((float)channel_pitch->control_in / 4000.0f); float pitch_trim_adjustment = ToRad((float)channel_pitch->get_control_in() / 4000.0f);
// add trim to ahrs object // add trim to ahrs object
// save to eeprom on last iteration // save to eeprom on last iteration

View File

@ -12,17 +12,17 @@
void Copter::tuning() { void Copter::tuning() {
// exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero // exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || g.rc_6.radio_in == 0) { if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || g.rc_6.get_radio_in() == 0) {
return; return;
} }
// set tuning range and then get new value // set tuning range and then get new value
g.rc_6.set_range_in(g.radio_tuning_low,g.radio_tuning_high); g.rc_6.set_range_in(g.radio_tuning_low,g.radio_tuning_high);
float tuning_value = (float)g.rc_6.control_in / 1000.0f; float tuning_value = (float)g.rc_6.get_control_in() / 1000.0f;
// Tuning Value should never be outside the bounds of the specified low and high value // Tuning Value should never be outside the bounds of the specified low and high value
tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f); tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f);
Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g.rc_6.control_in, g.radio_tuning_low, g.radio_tuning_high); Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g.rc_6.get_control_in(), g.radio_tuning_low, g.radio_tuning_high);
switch(g.radio_tuning) { switch(g.radio_tuning) {
@ -96,7 +96,7 @@ void Copter::tuning() {
case TUNING_WP_SPEED: case TUNING_WP_SPEED:
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s // set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
wp_nav.set_speed_xy(g.rc_6.control_in); wp_nav.set_speed_xy(g.rc_6.get_control_in());
break; break;
// Acro roll pitch gain // Acro roll pitch gain
@ -111,7 +111,7 @@ void Copter::tuning() {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
case TUNING_HELI_EXTERNAL_GYRO: case TUNING_HELI_EXTERNAL_GYRO:
motors.ext_gyro_gain((float)g.rc_6.control_in / 1000.0f); motors.ext_gyro_gain((float)g.rc_6.get_control_in() / 1000.0f);
break; break;
case TUNING_RATE_PITCH_FF: case TUNING_RATE_PITCH_FF:
@ -129,12 +129,12 @@ void Copter::tuning() {
case TUNING_DECLINATION: case TUNING_DECLINATION:
// set declination to +-20degrees // set declination to +-20degrees
compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact compass.set_declination(ToRad((2.0f * g.rc_6.get_control_in() - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
break; break;
case TUNING_CIRCLE_RATE: case TUNING_CIRCLE_RATE:
// set circle rate up to approximately 45 deg/sec in either direction // set circle rate up to approximately 45 deg/sec in either direction
circle_nav.set_rate((float)g.rc_6.control_in/25.0f-20.0f); circle_nav.set_rate((float)g.rc_6.get_control_in()/25.0f-20.0f);
break; break;
case TUNING_SONAR_GAIN: case TUNING_SONAR_GAIN:
@ -175,7 +175,7 @@ void Copter::tuning() {
case TUNING_RC_FEEL_RP: case TUNING_RC_FEEL_RP:
// roll-pitch input smoothing // roll-pitch input smoothing
g.rc_feel_rp = g.rc_6.control_in / 10; g.rc_feel_rp = g.rc_6.get_control_in() / 10;
break; break;
case TUNING_RATE_PITCH_KP: case TUNING_RATE_PITCH_KP: