mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Copter: added channel objects named after input function
this follows the pattern used in plane and rover
This commit is contained in:
parent
d48bd8708b
commit
554de1f2d7
@ -210,6 +210,12 @@ static uint8_t command_ack_counter;
|
||||
// has a log download started?
|
||||
static bool in_log_download;
|
||||
|
||||
// primary input control channels
|
||||
static RC_Channel *channel_roll;
|
||||
static RC_Channel *channel_pitch;
|
||||
static RC_Channel *channel_throttle;
|
||||
static RC_Channel *channel_yaw;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// prototypes
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -422,15 +428,15 @@ static struct {
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7, g.rc_8, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE);
|
||||
static MOTOR_CLASS motors(*channel_roll, *channel_pitch, *channel_throttle, *channel_yaw, g.rc_7, g.rc_8, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE);
|
||||
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7, MAIN_LOOP_RATE);
|
||||
static MOTOR_CLASS motors(*channel_roll, *channel_pitch, *channel_throttle, *channel_yaw, g.rc_7, MAIN_LOOP_RATE);
|
||||
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4, MAIN_LOOP_RATE);
|
||||
static MOTOR_CLASS motors(*channel_roll, *channel_pitch, *channel_throttle, *channel_yaw, g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4, MAIN_LOOP_RATE);
|
||||
#elif FRAME_CONFIG == COAX_FRAME // single constructor requires extra servos for flaps
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2, MAIN_LOOP_RATE);
|
||||
static MOTOR_CLASS motors(*channel_roll, *channel_pitch, *channel_throttle, *channel_yaw, g.single_servo_1, g.single_servo_2, MAIN_LOOP_RATE);
|
||||
#else
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, MAIN_LOOP_RATE);
|
||||
static MOTOR_CLASS motors(*channel_roll, *channel_pitch, *channel_throttle, *channel_yaw, MAIN_LOOP_RATE);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -949,7 +955,7 @@ static void update_batt_compass(void)
|
||||
|
||||
if(g.compass_enabled) {
|
||||
// update compass with throttle value - used for compassmot
|
||||
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
|
||||
compass.set_throttle((float)channel_throttle->servo_out/1000.0f);
|
||||
compass.read();
|
||||
// log compass information
|
||||
if (should_log(MASK_LOG_COMPASS)) {
|
||||
@ -1157,17 +1163,17 @@ void update_simple_mode(void)
|
||||
|
||||
if (ap.simple_mode == 1) {
|
||||
// rotate roll, pitch input by -initial simple heading (i.e. north facing)
|
||||
rollx = g.rc_1.control_in*simple_cos_yaw - g.rc_2.control_in*simple_sin_yaw;
|
||||
pitchx = g.rc_1.control_in*simple_sin_yaw + g.rc_2.control_in*simple_cos_yaw;
|
||||
rollx = channel_roll->control_in*simple_cos_yaw - channel_pitch->control_in*simple_sin_yaw;
|
||||
pitchx = channel_roll->control_in*simple_sin_yaw + channel_pitch->control_in*simple_cos_yaw;
|
||||
}else{
|
||||
// rotate roll, pitch input by -super simple heading (reverse of heading to home)
|
||||
rollx = g.rc_1.control_in*super_simple_cos_yaw - g.rc_2.control_in*super_simple_sin_yaw;
|
||||
pitchx = g.rc_1.control_in*super_simple_sin_yaw + g.rc_2.control_in*super_simple_cos_yaw;
|
||||
rollx = channel_roll->control_in*super_simple_cos_yaw - channel_pitch->control_in*super_simple_sin_yaw;
|
||||
pitchx = channel_roll->control_in*super_simple_sin_yaw + channel_pitch->control_in*super_simple_cos_yaw;
|
||||
}
|
||||
|
||||
// rotate roll, pitch input from north facing to vehicle's perspective
|
||||
g.rc_1.control_in = rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw();
|
||||
g.rc_2.control_in = -rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw();
|
||||
channel_roll->control_in = rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw();
|
||||
channel_pitch->control_in = -rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw();
|
||||
}
|
||||
|
||||
// update_super_simple_bearing - adjusts simple bearing based on location
|
||||
|
@ -94,7 +94,7 @@ static void update_thr_average()
|
||||
}
|
||||
|
||||
// get throttle output
|
||||
int16_t throttle = g.rc_3.servo_out;
|
||||
int16_t throttle = channel_throttle->servo_out;
|
||||
|
||||
// calc average throttle if we are in a level hover
|
||||
if (throttle > g.throttle_min && abs(climb_rate) < 60 && labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
|
||||
@ -122,7 +122,7 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
|
||||
{
|
||||
int16_t throttle_out;
|
||||
|
||||
int16_t mid_stick = g.rc_3.get_control_mid();
|
||||
int16_t mid_stick = channel_throttle->get_control_mid();
|
||||
|
||||
// ensure reasonable throttle values
|
||||
throttle_control = constrain_int16(throttle_control,0,1000);
|
||||
|
@ -397,7 +397,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
gps.ground_speed(),
|
||||
gps.ground_speed(),
|
||||
(ahrs.yaw_sensor / 100) % 360,
|
||||
g.rc_3.servo_out/10,
|
||||
channel_throttle->servo_out/10,
|
||||
current_loc.alt / 100.0f,
|
||||
climb_rate / 100.0f);
|
||||
}
|
||||
|
@ -216,7 +216,7 @@ static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
|
||||
// Write a Current data packet
|
||||
static void Log_Write_Current()
|
||||
{
|
||||
DataFlash.Log_Write_Current(battery, g.rc_3.servo_out);
|
||||
DataFlash.Log_Write_Current(battery, channel_throttle->servo_out);
|
||||
|
||||
// also write power status
|
||||
DataFlash.Log_Write_Power();
|
||||
@ -317,9 +317,9 @@ static void Log_Write_Control_Tuning()
|
||||
struct log_Control_Tuning pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
throttle_in : g.rc_3.control_in,
|
||||
throttle_in : channel_throttle->control_in,
|
||||
angle_boost : attitude_control.angle_boost(),
|
||||
throttle_out : g.rc_3.servo_out,
|
||||
throttle_out : channel_throttle->servo_out,
|
||||
desired_alt : pos_control.get_alt_target() / 100.0f,
|
||||
inav_alt : inertial_nav.get_altitude() / 100.0f,
|
||||
baro_alt : baro_alt,
|
||||
|
@ -56,7 +56,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan)
|
||||
|
||||
// check throttle is at zero
|
||||
read_radio();
|
||||
if (g.rc_3.control_in != 0) {
|
||||
if (channel_throttle->control_in != 0) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(SEVERITY_HIGH, PSTR("thr not zero"));
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
@ -146,7 +146,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan)
|
||||
read_radio();
|
||||
|
||||
// pass through throttle to motors
|
||||
motors.throttle_pass_through(g.rc_3.radio_in);
|
||||
motors.throttle_pass_through(channel_throttle->radio_in);
|
||||
|
||||
// read some compass values
|
||||
compass.read();
|
||||
@ -155,7 +155,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan)
|
||||
read_battery();
|
||||
|
||||
// calculate scaling for throttle
|
||||
throttle_pct = (float)g.rc_3.control_in / 1000.0f;
|
||||
throttle_pct = (float)channel_throttle->control_in / 1000.0f;
|
||||
throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
|
||||
|
||||
// if throttle is near zero, update base x,y,z values
|
||||
@ -218,7 +218,7 @@ static uint8_t mavlink_compassmot(mavlink_channel_t chan)
|
||||
if (hal.scheduler->millis() - last_send_time > 500) {
|
||||
last_send_time = hal.scheduler->millis();
|
||||
mavlink_msg_compassmot_status_send(chan,
|
||||
g.rc_3.control_in,
|
||||
channel_throttle->control_in,
|
||||
battery.current_amps(),
|
||||
interference_pct[compass.get_primary()],
|
||||
motor_compensation[compass.get_primary()].x,
|
||||
|
@ -29,7 +29,7 @@ static void althold_run()
|
||||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -64,8 +64,8 @@ static void althold_run()
|
||||
|
||||
// reset target lean angles and heading while landed
|
||||
if (ap.land_complete) {
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
}else{
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
@ -124,7 +124,7 @@ static void auto_takeoff_run()
|
||||
float target_yaw_rate = 0;
|
||||
if (!failsafe.radio) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// run waypoint controller
|
||||
@ -301,12 +301,12 @@ static void auto_land_run()
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
roll_control = channel_roll->control_in;
|
||||
pitch_control = channel_pitch->control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// process roll, pitch inputs
|
||||
@ -456,7 +456,7 @@ void auto_loiter_run()
|
||||
// accept pilot input of yaw
|
||||
float target_yaw_rate = 0;
|
||||
if(!failsafe.radio) {
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// run waypoint and z-axis postion controller
|
||||
|
@ -263,7 +263,7 @@ static void autotune_run()
|
||||
// this should not actually be possible because of the autotune_init() checks
|
||||
if (!ap.auto_armed || !motors.get_interlock()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -271,13 +271,13 @@ static void autotune_run()
|
||||
update_simple_mode();
|
||||
|
||||
// get pilot desired lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
|
||||
// get pilot desired climb rate
|
||||
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
|
||||
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in);
|
||||
|
||||
// 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) {
|
||||
@ -290,7 +290,7 @@ static void autotune_run()
|
||||
// reset target lean angles and heading while landed
|
||||
if (ap.land_complete) {
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true,g.throttle_filt);
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
pos_control.set_alt_target_to_current_alt();
|
||||
}else{
|
||||
// check if pilot is overriding the controls
|
||||
|
@ -53,10 +53,10 @@ static void drift_run()
|
||||
}
|
||||
|
||||
// convert pilot input to lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
|
||||
// get pilot's desired throttle
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in);
|
||||
|
||||
// Grab inertial velocity
|
||||
const Vector3f& vel = inertial_nav.get_velocity();
|
||||
@ -72,7 +72,7 @@ static void drift_run()
|
||||
roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
|
||||
pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
|
||||
|
||||
roll_input = roll_input * .96f + (float)g.rc_4.control_in * .04f;
|
||||
roll_input = roll_input * .96f + (float)channel_yaw->control_in * .04f;
|
||||
|
||||
//convert user input into desired roll velocity
|
||||
float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);
|
||||
|
@ -69,11 +69,11 @@ static bool flip_init(bool ignore_checks)
|
||||
flip_roll_dir = flip_pitch_dir = 0;
|
||||
|
||||
// choose direction based on pilot's roll and pitch sticks
|
||||
if (g.rc_2.control_in > 300) {
|
||||
if (channel_pitch->control_in > 300) {
|
||||
flip_pitch_dir = FLIP_PITCH_BACK;
|
||||
}else if(g.rc_2.control_in < -300) {
|
||||
}else if(channel_pitch->control_in < -300) {
|
||||
flip_pitch_dir = FLIP_PITCH_FORWARD;
|
||||
}else if (g.rc_1.control_in >= 0) {
|
||||
}else if (channel_roll->control_in >= 0) {
|
||||
flip_roll_dir = FLIP_ROLL_RIGHT;
|
||||
}else{
|
||||
flip_roll_dir = FLIP_ROLL_LEFT;
|
||||
@ -98,12 +98,12 @@ static void flip_run()
|
||||
float recovery_angle;
|
||||
|
||||
// if pilot inputs roll > 40deg or timeout occurs abandon flip
|
||||
if (!motors.armed() || (abs(g.rc_1.control_in) >= 4000) || (abs(g.rc_2.control_in) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) {
|
||||
if (!motors.armed() || (abs(channel_roll->control_in) >= 4000) || (abs(channel_pitch->control_in) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) {
|
||||
flip_state = Flip_Abandon;
|
||||
}
|
||||
|
||||
// get pilot's desired throttle
|
||||
throttle_out = get_pilot_desired_throttle(g.rc_3.control_in);
|
||||
throttle_out = get_pilot_desired_throttle(channel_throttle->control_in);
|
||||
|
||||
// get corrected angle based on direction and axis of rotation
|
||||
// we flip the sign of flip_angle to minimize the code repetition
|
||||
|
@ -210,7 +210,7 @@ static void guided_takeoff_run()
|
||||
float target_yaw_rate = 0;
|
||||
if (!failsafe.radio) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// run waypoint controller
|
||||
|
@ -81,12 +81,12 @@ static void land_gps_run()
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
roll_control = channel_roll->control_in;
|
||||
pitch_control = channel_pitch->control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// process roll, pitch inputs
|
||||
@ -147,11 +147,11 @@ static void land_nogps_run()
|
||||
update_simple_mode();
|
||||
|
||||
// get pilot desired lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// call attitude controller
|
||||
|
@ -37,7 +37,7 @@ static void loiter_run()
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -84,8 +84,8 @@ static void loiter_run()
|
||||
if (ap.land_complete) {
|
||||
wp_nav.init_loiter_target();
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
}else{
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
@ -146,7 +146,7 @@ static void poshold_run()
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
wp_nav.init_loiter_target();
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -187,12 +187,12 @@ static void poshold_run()
|
||||
if (ap.land_complete) {
|
||||
wp_nav.init_loiter_target();
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
}else{
|
||||
// convert pilot input to lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
|
||||
// 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)
|
||||
|
@ -272,12 +272,12 @@ static void rtl_descent_run()
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
roll_control = channel_roll->control_in;
|
||||
pitch_control = channel_pitch->control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// process roll, pitch inputs
|
||||
@ -354,12 +354,12 @@ static void rtl_land_run()
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
roll_control = channel_roll->control_in;
|
||||
pitch_control = channel_pitch->control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
}
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
|
@ -38,8 +38,8 @@ static void sport_run()
|
||||
// get pilot's desired roll and pitch rates
|
||||
|
||||
// calculate rate requests
|
||||
target_roll_rate = g.rc_1.control_in * g.acro_rp_p;
|
||||
target_pitch_rate = g.rc_2.control_in * g.acro_rp_p;
|
||||
target_roll_rate = channel_roll->control_in * g.acro_rp_p;
|
||||
target_pitch_rate = channel_pitch->control_in * g.acro_rp_p;
|
||||
|
||||
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;
|
||||
@ -85,8 +85,8 @@ static void sport_run()
|
||||
// reset target lean angles and heading while landed
|
||||
if (ap.land_complete) {
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
}else{
|
||||
|
||||
// call attitude controller
|
||||
|
@ -34,13 +34,13 @@ static void stabilize_run()
|
||||
|
||||
// convert pilot input to lean angles
|
||||
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
|
||||
// get pilot's desired throttle
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
@ -31,7 +31,7 @@ static void esc_calibration_startup_check()
|
||||
switch (g.esc_calibrate) {
|
||||
case ESCCAL_NONE:
|
||||
// check if throttle is high
|
||||
if (g.rc_3.control_in >= ESC_CALIBRATION_HIGH_THROTTLE) {
|
||||
if (channel_throttle->control_in >= ESC_CALIBRATION_HIGH_THROTTLE) {
|
||||
// we will enter esc_calibrate mode on next reboot
|
||||
g.esc_calibrate.set_and_save(ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
|
||||
// send message to gcs
|
||||
@ -44,7 +44,7 @@ static void esc_calibration_startup_check()
|
||||
break;
|
||||
case ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:
|
||||
// check if throttle is high
|
||||
if (g.rc_3.control_in >= ESC_CALIBRATION_HIGH_THROTTLE) {
|
||||
if (channel_throttle->control_in >= ESC_CALIBRATION_HIGH_THROTTLE) {
|
||||
// pass through pilot throttle to escs
|
||||
esc_calibration_passthrough();
|
||||
}
|
||||
@ -90,7 +90,7 @@ static void esc_calibration_passthrough()
|
||||
delay(10);
|
||||
|
||||
// pass through to motors
|
||||
motors.throttle_pass_through(g.rc_3.radio_in);
|
||||
motors.throttle_pass_through(channel_throttle->radio_in);
|
||||
}
|
||||
}
|
||||
|
||||
@ -114,7 +114,7 @@ static void esc_calibration_auto()
|
||||
|
||||
// raise throttle to maximum
|
||||
delay(10);
|
||||
motors.throttle_pass_through(g.rc_3.radio_max);
|
||||
motors.throttle_pass_through(channel_throttle->radio_max);
|
||||
|
||||
// wait for safety switch to be pressed
|
||||
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
@ -129,7 +129,7 @@ static void esc_calibration_auto()
|
||||
delay(5000);
|
||||
|
||||
// reduce throttle to minimum
|
||||
motors.throttle_pass_through(g.rc_3.radio_min);
|
||||
motors.throttle_pass_through(channel_throttle->radio_min);
|
||||
|
||||
// clear esc parameter
|
||||
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
||||
|
@ -230,7 +230,7 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
|
||||
// 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) {
|
||||
// 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(g.rc_3.control_in));
|
||||
set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(channel_throttle->control_in));
|
||||
}
|
||||
|
||||
// cancel any takeoffs in progress
|
||||
|
@ -21,7 +21,7 @@ static void heli_init()
|
||||
motors.recalc_scalers();
|
||||
}
|
||||
|
||||
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the g.rc_3.servo_out function
|
||||
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the channel_throttle->servo_out function
|
||||
static int16_t get_pilot_desired_collective(int16_t control_in)
|
||||
{
|
||||
// return immediately if reduce collective range for manual flight has not been configured
|
||||
@ -56,7 +56,7 @@ static void check_dynamic_flight(void)
|
||||
moving = (velocity >= HELI_DYNAMIC_FLIGHT_SPEED_MIN);
|
||||
}else{
|
||||
// with no GPS lock base it on throttle and forward lean angle
|
||||
moving = (g.rc_3.servo_out > 800 || ahrs.pitch_sensor < -1500);
|
||||
moving = (channel_throttle->servo_out > 800 || ahrs.pitch_sensor < -1500);
|
||||
}
|
||||
|
||||
if (moving) {
|
||||
|
@ -38,18 +38,18 @@ static void heli_acro_run()
|
||||
|
||||
if (!motors.has_flybar()){
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw);
|
||||
get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw);
|
||||
// run attitude controller
|
||||
attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
|
||||
}else{
|
||||
// flybar helis only need yaw rate control
|
||||
get_pilot_desired_yaw_rate(g.rc_4.control_in, target_yaw);
|
||||
get_pilot_desired_yaw_rate(channel_yaw->control_in, target_yaw);
|
||||
// run attitude controller
|
||||
attitude_control.passthrough_bf_roll_pitch_rate_yaw(g.rc_1.control_in, g.rc_2.control_in, target_yaw);
|
||||
attitude_control.passthrough_bf_roll_pitch_rate_yaw(channel_roll->control_in, channel_pitch->control_in, target_yaw);
|
||||
}
|
||||
|
||||
// output pilot's throttle without angle boost
|
||||
attitude_control.set_throttle_out(g.rc_3.control_in, false, g.throttle_filt);
|
||||
attitude_control.set_throttle_out(channel_throttle->control_in, false, g.throttle_filt);
|
||||
}
|
||||
|
||||
// get_pilot_desired_yaw_rate - transform pilot's yaw input into a desired yaw angle rate
|
||||
|
@ -42,13 +42,13 @@ static void heli_stabilize_run()
|
||||
|
||||
// convert pilot input to lean angles
|
||||
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
||||
|
||||
// get pilot's desired throttle
|
||||
pilot_throttle_scaled = get_pilot_desired_collective(g.rc_3.control_in);
|
||||
pilot_throttle_scaled = get_pilot_desired_collective(channel_throttle->control_in);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
@ -37,7 +37,7 @@ static void motor_test_output()
|
||||
case MOTOR_TEST_THROTTLE_PERCENT:
|
||||
// sanity check motor_test_throttle value
|
||||
if (motor_test_throttle_value <= 100) {
|
||||
pwm = g.rc_3.radio_min + (g.rc_3.radio_max - g.rc_3.radio_min) * (float)motor_test_throttle_value/100.0f;
|
||||
pwm = channel_throttle->radio_min + (channel_throttle->radio_max - channel_throttle->radio_min) * (float)motor_test_throttle_value/100.0f;
|
||||
}
|
||||
break;
|
||||
|
||||
@ -46,7 +46,7 @@ static void motor_test_output()
|
||||
break;
|
||||
|
||||
case MOTOR_TEST_THROTTLE_PILOT:
|
||||
pwm = g.rc_3.radio_in;
|
||||
pwm = channel_throttle->radio_in;
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -16,12 +16,12 @@ static void arm_motors_check()
|
||||
static int16_t arming_counter;
|
||||
|
||||
// ensure throttle is down
|
||||
if (g.rc_3.control_in > 0) {
|
||||
if (channel_throttle->control_in > 0) {
|
||||
arming_counter = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
int16_t tmp = g.rc_4.control_in;
|
||||
int16_t tmp = channel_yaw->control_in;
|
||||
|
||||
// full right
|
||||
if (tmp > 4000) {
|
||||
@ -487,7 +487,7 @@ static bool pre_arm_checks(bool display_failure)
|
||||
// failsafe parameter checks
|
||||
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
|
||||
if (g.rc_3.radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
|
||||
if (channel_throttle->radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check FS_THR_VALUE"));
|
||||
}
|
||||
@ -542,27 +542,27 @@ static void pre_arm_rc_checks()
|
||||
}
|
||||
|
||||
// check if radio has been calibrated
|
||||
if(!g.rc_3.radio_min.load() && !g.rc_3.radio_max.load()) {
|
||||
if(!channel_throttle->radio_min.load() && !channel_throttle->radio_max.load()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check channels 1 & 2 have min <= 1300 and max >= 1700
|
||||
if (g.rc_1.radio_min > 1300 || g.rc_1.radio_max < 1700 || g.rc_2.radio_min > 1300 || g.rc_2.radio_max < 1700) {
|
||||
if (channel_roll->radio_min > 1300 || channel_roll->radio_max < 1700 || channel_pitch->radio_min > 1300 || channel_pitch->radio_max < 1700) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check channels 3 & 4 have min <= 1300 and max >= 1700
|
||||
if (g.rc_3.radio_min > 1300 || g.rc_3.radio_max < 1700 || g.rc_4.radio_min > 1300 || g.rc_4.radio_max < 1700) {
|
||||
if (channel_throttle->radio_min > 1300 || channel_throttle->radio_max < 1700 || channel_yaw->radio_min > 1300 || channel_yaw->radio_max < 1700) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check channels 1 & 2 have trim >= 1300 and <= 1700
|
||||
if (g.rc_1.radio_trim < 1300 || g.rc_1.radio_trim > 1700 || g.rc_2.radio_trim < 1300 || g.rc_2.radio_trim > 1700) {
|
||||
if (channel_roll->radio_trim < 1300 || channel_roll->radio_trim > 1700 || channel_pitch->radio_trim < 1300 || channel_pitch->radio_trim > 1700) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check channel 4 has trim >= 1300 and <= 1700
|
||||
if (g.rc_4.radio_trim < 1300 || g.rc_4.radio_trim > 1700) {
|
||||
if (channel_yaw->radio_trim < 1300 || channel_yaw->radio_trim > 1700) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -709,7 +709,7 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
|
||||
// check throttle
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
||||
// check throttle is not too low - must be above failsafe throttle
|
||||
if (g.failsafe_throttle != FS_THR_DISABLED && g.rc_3.radio_in < g.failsafe_throttle_value) {
|
||||
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle below Failsafe"));
|
||||
}
|
||||
|
@ -5,30 +5,35 @@
|
||||
|
||||
static void default_dead_zones()
|
||||
{
|
||||
g.rc_1.set_default_dead_zone(30);
|
||||
g.rc_2.set_default_dead_zone(30);
|
||||
channel_roll->set_default_dead_zone(30);
|
||||
channel_pitch->set_default_dead_zone(30);
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
g.rc_3.set_default_dead_zone(10);
|
||||
g.rc_4.set_default_dead_zone(15);
|
||||
channel_throttle->set_default_dead_zone(10);
|
||||
channel_yaw->set_default_dead_zone(15);
|
||||
g.rc_8.set_default_dead_zone(10);
|
||||
#else
|
||||
g.rc_3.set_default_dead_zone(30);
|
||||
g.rc_4.set_default_dead_zone(40);
|
||||
channel_throttle->set_default_dead_zone(30);
|
||||
channel_yaw->set_default_dead_zone(40);
|
||||
#endif
|
||||
g.rc_6.set_default_dead_zone(0);
|
||||
}
|
||||
|
||||
static void init_rc_in()
|
||||
{
|
||||
// set rc channel ranges
|
||||
g.rc_1.set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
g.rc_2.set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
g.rc_3.set_range(g.throttle_min, THR_MAX);
|
||||
g.rc_4.set_angle(4500);
|
||||
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
||||
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
||||
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
||||
channel_yaw = RC_Channel::rc_channel(rcmap.yaw()-1);
|
||||
|
||||
g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
g.rc_2.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
g.rc_4.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
// set rc channel ranges
|
||||
channel_roll->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
channel_pitch->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
channel_yaw->set_angle(4500);
|
||||
channel_throttle->set_range(g.throttle_min, THR_MAX);
|
||||
|
||||
channel_roll->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
channel_pitch->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
channel_yaw->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
|
||||
//set auxiliary servo ranges
|
||||
g.rc_5.set_range(0,1000);
|
||||
@ -57,7 +62,7 @@ static void init_rc_out()
|
||||
}
|
||||
|
||||
// we want the input to be scaled correctly
|
||||
g.rc_3.set_range_out(0,1000);
|
||||
channel_throttle->set_range_out(0,1000);
|
||||
|
||||
// check if we should enter esc calibration mode
|
||||
esc_calibration_startup_check();
|
||||
@ -69,9 +74,8 @@ static void init_rc_out()
|
||||
}
|
||||
|
||||
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
||||
// take a proportion of speed. Note: this assumes rc_3 is
|
||||
// throttle and should really use rcmap.
|
||||
hal.rcout->set_esc_scaling(g.rc_3.radio_min, g.rc_3.radio_max);
|
||||
// take a proportion of speed.
|
||||
hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max);
|
||||
}
|
||||
|
||||
// enable_motor_output() - enable and output lowest possible value to motors
|
||||
@ -90,26 +94,10 @@ static void read_radio()
|
||||
if (hal.rcin->new_input()) {
|
||||
last_update_ms = tnow_ms;
|
||||
ap.new_radio_frame = true;
|
||||
uint16_t periods[8];
|
||||
hal.rcin->read(periods,8);
|
||||
g.rc_1.set_pwm(periods[rcmap.roll()-1]);
|
||||
g.rc_2.set_pwm(periods[rcmap.pitch()-1]);
|
||||
RC_Channel::set_pwm_all();
|
||||
|
||||
set_throttle_and_failsafe(periods[rcmap.throttle()-1]);
|
||||
set_throttle_zero_flag(g.rc_3.control_in);
|
||||
|
||||
g.rc_4.set_pwm(periods[rcmap.yaw()-1]);
|
||||
g.rc_5.set_pwm(periods[4]);
|
||||
g.rc_6.set_pwm(periods[5]);
|
||||
g.rc_7.set_pwm(periods[6]);
|
||||
g.rc_8.set_pwm(periods[7]);
|
||||
|
||||
// read channels 9 ~ 14
|
||||
for (uint8_t i=8; i<RC_MAX_CHANNELS; i++) {
|
||||
if (RC_Channel::rc_channel(i) != NULL) {
|
||||
RC_Channel::rc_channel(i)->set_pwm(RC_Channel::rc_channel(i)->read());
|
||||
}
|
||||
}
|
||||
set_throttle_and_failsafe(channel_throttle->radio_in);
|
||||
set_throttle_zero_flag(channel_throttle->control_in);
|
||||
|
||||
// flag we must have an rc receiver attached
|
||||
if (!failsafe.rc_override_active) {
|
||||
@ -134,7 +122,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
|
||||
{
|
||||
// if failsafe not enabled pass through throttle and exit
|
||||
if(g.failsafe_throttle == FS_THR_DISABLED) {
|
||||
g.rc_3.set_pwm(throttle_pwm);
|
||||
channel_throttle->set_pwm(throttle_pwm);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -143,7 +131,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
|
||||
|
||||
// if we are already in failsafe or motors not armed pass through throttle and exit
|
||||
if (failsafe.radio || !(ap.rc_receiver_present || motors.armed())) {
|
||||
g.rc_3.set_pwm(throttle_pwm);
|
||||
channel_throttle->set_pwm(throttle_pwm);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -153,7 +141,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
|
||||
if( failsafe.radio_counter >= FS_COUNTER ) {
|
||||
failsafe.radio_counter = FS_COUNTER; // check to ensure we don't overflow the counter
|
||||
set_failsafe_radio(true);
|
||||
g.rc_3.set_pwm(throttle_pwm); // pass through failsafe throttle
|
||||
channel_throttle->set_pwm(throttle_pwm); // pass through failsafe throttle
|
||||
}
|
||||
}else{
|
||||
// we have a good throttle so reduce failsafe counter
|
||||
@ -167,7 +155,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
|
||||
}
|
||||
}
|
||||
// pass through throttle
|
||||
g.rc_3.set_pwm(throttle_pwm);
|
||||
channel_throttle->set_pwm(throttle_pwm);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -403,10 +403,10 @@ void report_optflow()
|
||||
static void
|
||||
print_radio_values()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("CH1: %d | %d\n"), (int)g.rc_1.radio_min, (int)g.rc_1.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH2: %d | %d\n"), (int)g.rc_2.radio_min, (int)g.rc_2.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH3: %d | %d\n"), (int)g.rc_3.radio_min, (int)g.rc_3.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH4: %d | %d\n"), (int)g.rc_4.radio_min, (int)g.rc_4.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH1: %d | %d\n"), (int)channel_roll->radio_min, (int)channel_roll->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH2: %d | %d\n"), (int)channel_pitch->radio_min, (int)channel_pitch->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH3: %d | %d\n"), (int)channel_throttle->radio_min, (int)channel_throttle->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH4: %d | %d\n"), (int)channel_yaw->radio_min, (int)channel_yaw->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH5: %d | %d\n"), (int)g.rc_5.radio_min, (int)g.rc_5.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH6: %d | %d\n"), (int)g.rc_6.radio_min, (int)g.rc_6.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH7: %d | %d\n"), (int)g.rc_7.radio_min, (int)g.rc_7.radio_max);
|
||||
|
@ -288,7 +288,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
break;
|
||||
|
||||
case AUXSW_SAVE_TRIM:
|
||||
if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (g.rc_3.control_in == 0)) {
|
||||
if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (channel_throttle->control_in == 0)) {
|
||||
save_trim();
|
||||
}
|
||||
break;
|
||||
@ -332,7 +332,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
cmd.content.location = current_loc;
|
||||
|
||||
// if throttle is above zero, create waypoint command
|
||||
if(g.rc_3.control_in > 0) {
|
||||
if(channel_throttle->control_in > 0) {
|
||||
cmd.id = MAV_CMD_NAV_WAYPOINT;
|
||||
}else{
|
||||
// with zero throttle, create LAND command
|
||||
@ -591,8 +591,8 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
static void save_trim()
|
||||
{
|
||||
// save roll and pitch trim
|
||||
float roll_trim = ToRad((float)g.rc_1.control_in/100.0f);
|
||||
float pitch_trim = ToRad((float)g.rc_2.control_in/100.0f);
|
||||
float roll_trim = ToRad((float)channel_roll->control_in/100.0f);
|
||||
float pitch_trim = ToRad((float)channel_pitch->control_in/100.0f);
|
||||
ahrs.add_trim(roll_trim, pitch_trim);
|
||||
Log_Write_Event(DATA_SAVE_TRIM);
|
||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("Trim saved"));
|
||||
@ -609,10 +609,10 @@ static void auto_trim()
|
||||
AP_Notify::flags.save_trim = true;
|
||||
|
||||
// calculate roll trim adjustment
|
||||
float roll_trim_adjustment = ToRad((float)g.rc_1.control_in / 4000.0f);
|
||||
float roll_trim_adjustment = ToRad((float)channel_roll->control_in / 4000.0f);
|
||||
|
||||
// calculate pitch trim adjustment
|
||||
float pitch_trim_adjustment = ToRad((float)g.rc_2.control_in / 4000.0f);
|
||||
float pitch_trim_adjustment = ToRad((float)channel_pitch->control_in / 4000.0f);
|
||||
|
||||
// add trim to ahrs object
|
||||
// save to eeprom on last iteration
|
||||
|
Loading…
Reference in New Issue
Block a user