ArduCopter: RC_Channel refactor

More fixing up of RC_Channel change direct access to data members
to access via member functions.
This commit is contained in:
skyscraper 2016-05-09 09:02:31 +01:00 committed by Andrew Tridgell
parent 49d3410896
commit 4980c8bc94
2 changed files with 9 additions and 9 deletions

View File

@ -349,10 +349,10 @@ void NOINLINE Copter::send_servo_out(mavlink_channel_t chan)
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
g.rc_3.radio_out,
g.rc_4.servo_out,
g.rc_1.get_servo_out(),
g.rc_2.get_servo_out(),
g.rc_3.get_radio_out(),
g.rc_4.get_servo_out(),
0,
0,
0,
@ -363,10 +363,10 @@ void NOINLINE Copter::send_servo_out(mavlink_channel_t chan)
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
g.rc_3.radio_out,
g.rc_4.servo_out,
g.rc_1.get_servo_out(),
g.rc_2.get_servo_out(),
g.rc_3.get_radio_out(),
g.rc_4.get_servo_out(),
10000 * g.rc_1.norm_output(),
10000 * g.rc_2.norm_output(),
10000 * g.rc_3.norm_output(),

View File

@ -39,7 +39,7 @@ void Copter::update_ground_effect_detector(void)
}
// if we aren't taking off yet, reset the takeoff timer, altitude and complete flag
bool throttle_up = mode_has_manual_throttle(control_mode) && g.rc_3.control_in > 0;
bool throttle_up = mode_has_manual_throttle(control_mode) && g.rc_3.get_control_in() > 0;
if (!throttle_up && ap.land_complete) {
gndeffect_state.takeoff_time_ms = tnow_ms;
gndeffect_state.takeoff_alt_cm = inertial_nav.get_altitude();