Browse Source

Copter: AltHold limits lean angle to maintain altitude

get_pilot_desired_lean_angles function now takes angle max parameter but
all flight modes except AltHold simply pass in the ANGLE_MAX parameter
meaning no functional change for them
master
Leonard Hall 10 years ago committed by Randy Mackay
parent
commit
543f6fdcd4
  1. 12
      ArduCopter/Attitude.cpp
  2. 2
      ArduCopter/Copter.h
  3. 2
      ArduCopter/control_althold.cpp
  4. 2
      ArduCopter/control_autotune.cpp
  5. 2
      ArduCopter/control_drift.cpp
  6. 2
      ArduCopter/control_land.cpp
  7. 2
      ArduCopter/control_poshold.cpp
  8. 2
      ArduCopter/control_stabilize.cpp
  9. 2
      ArduCopter/heli_control_stabilize.cpp

12
ArduCopter/Attitude.cpp

@ -11,12 +11,16 @@ float Copter::get_smoothing_gain() @@ -11,12 +11,16 @@ float Copter::get_smoothing_gain()
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
// returns desired angle in centi-degrees
void Copter::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out)
void Copter::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max)
{
float angle_max = constrain_float(aparm.angle_max,1000,8000);
float scaler = (float)angle_max/(float)ROLL_PITCH_INPUT_MAX;
// sanity check angle max parameter
aparm.angle_max = constrain_int16(aparm.angle_max,1000,8000);
// scale roll_in, pitch_in to correct units
// limit max lean angle
angle_max = constrain_float(angle_max, 1000, aparm.angle_max);
// scale roll_in, pitch_in to ANGLE_MAX parameter range
float scaler = aparm.angle_max/(float)ROLL_PITCH_INPUT_MAX;
roll_in *= scaler;
pitch_in *= scaler;

2
ArduCopter/Copter.h

@ -567,7 +567,7 @@ private: @@ -567,7 +567,7 @@ private:
void set_using_interlock(bool b);
void set_motor_emergency_stop(bool b);
float get_smoothing_gain();
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out);
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
float get_pilot_desired_yaw_rate(int16_t stick_angle);
void check_ekf_yaw_reset();
float get_roi_yaw();

2
ArduCopter/control_althold.cpp

@ -34,7 +34,7 @@ void Copter::althold_run() @@ -34,7 +34,7 @@ void Copter::althold_run()
// get pilot desired lean angles
float target_roll, target_pitch;
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, 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's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);

2
ArduCopter/control_autotune.cpp

@ -273,7 +273,7 @@ void Copter::autotune_run() @@ -273,7 +273,7 @@ void Copter::autotune_run()
update_simple_mode();
// get pilot desired lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);

2
ArduCopter/control_drift.cpp

@ -55,7 +55,7 @@ void Copter::drift_run() @@ -55,7 +55,7 @@ void Copter::drift_run()
}
// convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in);

2
ArduCopter/control_land.cpp

@ -153,7 +153,7 @@ void Copter::land_nogps_run() @@ -153,7 +153,7 @@ void Copter::land_nogps_run()
update_simple_mode();
// get pilot desired lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
}
// get pilot's desired yaw rate

2
ArduCopter/control_poshold.cpp

@ -185,7 +185,7 @@ void Copter::poshold_run() @@ -185,7 +185,7 @@ void Copter::poshold_run()
return;
}else{
// convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
// 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)

2
ArduCopter/control_stabilize.cpp

@ -40,7 +40,7 @@ void Copter::stabilize_run() @@ -40,7 +40,7 @@ void Copter::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(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);

2
ArduCopter/heli_control_stabilize.cpp

@ -51,7 +51,7 @@ void Copter::heli_stabilize_run() @@ -51,7 +51,7 @@ void Copter::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(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch);
get_pilot_desired_lean_angles(channel_roll->control_in, channel_pitch->control_in, target_roll, target_pitch, aparm.angle_max);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);

Loading…
Cancel
Save