From edb5f0533965d97398d6e8f6ae8d11d1720d6b1d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 17 Oct 2019 15:03:48 +0900 Subject: [PATCH] Plane: minor comment changes --- ArduPlane/quadplane.cpp | 2 +- ArduPlane/radio.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 186fcf8b7c..1dd1bd4784 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -707,7 +707,7 @@ bool QuadPlane::setup(void) pos_control->set_dt(loop_delta_t); attitude_control->parameter_sanity_check(); - // setup the trim of any motors used by AP_Motors so px4io + // setup the trim of any motors used by AP_Motors so I/O board // failsafe will disable motors for (uint8_t i=0; i<8; i++) { SRV_Channel::Aux_servo_function_t func = SRV_Channels::get_motor_function(i); diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 727b66bc44..f30995cbc9 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -45,7 +45,7 @@ void Plane::set_control_channels(void) } if (!quadplane.enable) { - // setup correct scaling for ESCs like the UAVCAN PX4ESC which + // setup correct scaling for ESCs like the UAVCAN ESCs which // take a proportion of speed. For quadplanes we use AP_Motors // scaling g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); @@ -84,7 +84,7 @@ void Plane::init_rc_out_main() SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); - // setup PX4 to output the min throttle when safety off if arming + // setup flight controller to output the min throttle when safety off if arming // is setup for min on disarm if (arming.arming_required() == AP_Arming::Required::YES_MIN_PWM) { SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);