mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: call renamed functions in AC_AttitudeControl
This commit is contained in:
parent
1afab89991
commit
9d8b0f3d58
@ -2,7 +2,7 @@
|
||||
|
||||
#include "Copter.h"
|
||||
|
||||
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth
|
||||
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth
|
||||
// result is a number from 2 to 12 with 2 being very sluggish and 12 being very crisp
|
||||
float Copter::get_smoothing_gain()
|
||||
{
|
||||
|
@ -83,7 +83,7 @@ void Copter::althold_run()
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // Multicopter do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -122,7 +122,7 @@ void Copter::althold_run()
|
||||
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// call position controller
|
||||
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
||||
@ -135,7 +135,7 @@ void Copter::althold_run()
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.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);
|
||||
#else // Multicopter do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt);
|
||||
@ -145,7 +145,7 @@ void Copter::althold_run()
|
||||
|
||||
case AltHold_Flying:
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// call throttle controller
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
|
@ -117,7 +117,7 @@ void Copter::auto_takeoff_run()
|
||||
wp_nav.shift_wp_origin_to_current_pos();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
@ -142,7 +142,7 @@ void Copter::auto_takeoff_run()
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}
|
||||
|
||||
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
||||
@ -170,7 +170,7 @@ void Copter::auto_wp_run()
|
||||
// (of course it would be better if people just used take-off)
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -199,10 +199,10 @@ void Copter::auto_wp_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -234,7 +234,7 @@ void Copter::auto_spline_run()
|
||||
// (of course it would be better if people just used take-off)
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -263,10 +263,10 @@ void Copter::auto_spline_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(), true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(), true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -307,7 +307,7 @@ void Copter::auto_land_run()
|
||||
if(!ap.auto_armed || ap.land_complete) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -352,7 +352,7 @@ void Copter::auto_land_run()
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}
|
||||
|
||||
// auto_rtl_start - initialises RTL in AUTO flight mode
|
||||
@ -420,7 +420,7 @@ void Copter::auto_circle_run()
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true);
|
||||
}
|
||||
|
||||
#if NAV_GUIDED == ENABLED
|
||||
@ -479,7 +479,7 @@ void Copter::auto_loiter_run()
|
||||
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -496,7 +496,7 @@ void Copter::auto_loiter_run()
|
||||
// run waypoint and z-axis postion controller
|
||||
wp_nav.update_wpnav();
|
||||
pos_control.update_z_controller();
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}
|
||||
|
||||
// get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter
|
||||
|
@ -323,7 +323,7 @@ void Copter::autotune_run()
|
||||
|
||||
// if pilot override call attitude controller
|
||||
if (autotune_state.pilot_override || autotune_state.mode != AUTOTUNE_MODE_TUNING) {
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
}else{
|
||||
// somehow get attitude requests from autotuning
|
||||
autotune_attitude_control();
|
||||
@ -351,7 +351,7 @@ void Copter::autotune_attitude_control()
|
||||
attitude_control.limit_angle_to_rate_request(true);
|
||||
|
||||
// hold level attitude
|
||||
attitude_control.angle_ef_roll_pitch_yaw( 0.0f, 0.0f, autotune_desired_yaw, true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw( 0.0f, 0.0f, autotune_desired_yaw, true);
|
||||
|
||||
// hold the copter level for 0.5 seconds before we begin a twitch
|
||||
// reset counter if we are no longer level
|
||||
@ -430,22 +430,22 @@ void Copter::autotune_attitude_control()
|
||||
switch (autotune_state.axis) {
|
||||
case AUTOTUNE_AXIS_ROLL:
|
||||
// request roll to 20deg
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw( direction_sign * autotune_target_angle + autotune_start_angle, 0.0f, 0.0f);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw( direction_sign * autotune_target_angle + autotune_start_angle, 0.0f, 0.0f);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_PITCH:
|
||||
// request pitch to 20deg
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw( 0.0f, direction_sign * autotune_target_angle + autotune_start_angle, 0.0f);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw( 0.0f, direction_sign * autotune_target_angle + autotune_start_angle, 0.0f);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_YAW:
|
||||
// request pitch to 20deg
|
||||
attitude_control.angle_ef_roll_pitch_yaw( 0.0f, 0.0f, wrap_180_cd_float(direction_sign * autotune_target_angle + autotune_start_angle), false);
|
||||
attitude_control.euler_angle_roll_pitch_yaw( 0.0f, 0.0f, wrap_180_cd_float(direction_sign * autotune_target_angle + autotune_start_angle), false);
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
// Testing rate P and D gains so will set body-frame rate targets.
|
||||
// Rate controller will use existing body-frame rates and convert to motor outputs
|
||||
// for all axes except the one we override here.
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw( 0.0f, 0.0f, 0.0f);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw( 0.0f, 0.0f, 0.0f);
|
||||
switch (autotune_state.axis) {
|
||||
case AUTOTUNE_AXIS_ROLL:
|
||||
// override body-frame roll rate
|
||||
@ -721,7 +721,7 @@ void Copter::autotune_attitude_control()
|
||||
autotune_state.positive_direction = !autotune_state.positive_direction;
|
||||
|
||||
if (autotune_state.axis == AUTOTUNE_AXIS_YAW) {
|
||||
attitude_control.angle_ef_roll_pitch_yaw( 0.0f, 0.0f, ahrs.yaw_sensor, false);
|
||||
attitude_control.euler_angle_roll_pitch_yaw( 0.0f, 0.0f, ahrs.yaw_sensor, false);
|
||||
}
|
||||
|
||||
// set gains to their intra-test values (which are very close to the original gains)
|
||||
|
@ -40,7 +40,7 @@ void Copter::brake_run()
|
||||
wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE);
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -63,7 +63,7 @@ void Copter::brake_run()
|
||||
wp_nav.update_brake(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), 0.0f);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), 0.0f);
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
|
@ -46,7 +46,7 @@ void Copter::circle_run()
|
||||
// To-Do: add some initialisation of position controllers
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -80,9 +80,9 @@ void Copter::circle_run()
|
||||
|
||||
// call attitude controller
|
||||
if (circle_pilot_yaw_override) {
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
attitude_control.angle_ef_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true);
|
||||
}
|
||||
|
||||
// run altitude controller
|
||||
|
@ -94,7 +94,7 @@ void Copter::drift_run()
|
||||
}
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// output pilot's throttle with angle boost
|
||||
attitude_control.set_throttle_out(get_throttle_assist(vel.z, pilot_throttle_scaled), true, g.throttle_filt);
|
||||
|
@ -183,7 +183,7 @@ void Copter::flip_run()
|
||||
|
||||
case Flip_Recover:
|
||||
// use originally captured earth-frame angle targets to recover
|
||||
attitude_control.angle_ef_roll_pitch_yaw(flip_orig_attitude.x, flip_orig_attitude.y, flip_orig_attitude.z, false);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(flip_orig_attitude.x, flip_orig_attitude.y, flip_orig_attitude.z, false);
|
||||
|
||||
// increase throttle to gain any lost altitude
|
||||
throttle_out += FLIP_THR_INC;
|
||||
|
@ -254,7 +254,7 @@ void Copter::guided_takeoff_run()
|
||||
if (!ap.auto_armed || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -276,7 +276,7 @@ void Copter::guided_takeoff_run()
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}
|
||||
|
||||
// guided_pos_control_run - runs the guided position controller
|
||||
@ -287,7 +287,7 @@ void Copter::guided_pos_control_run()
|
||||
if (!ap.auto_armed || !motors.get_interlock() || ap.land_complete) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -314,10 +314,10 @@ void Copter::guided_pos_control_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(), true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(), true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -331,7 +331,7 @@ void Copter::guided_vel_control_run()
|
||||
pos_control.init_vel_controller_xyz();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -361,10 +361,10 @@ void Copter::guided_vel_control_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -379,7 +379,7 @@ void Copter::guided_posvel_control_run()
|
||||
pos_control.set_desired_velocity(Vector3f(0,0,0));
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -430,10 +430,10 @@ void Copter::guided_posvel_control_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -446,7 +446,7 @@ void Copter::guided_angle_control_run()
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0.0f, 0.0f, 0.0f, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0.0f, 0.0f, 0.0f, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0.0f,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);
|
||||
@ -481,7 +481,7 @@ void Copter::guided_angle_control_run()
|
||||
}
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);
|
||||
|
||||
// call position controller
|
||||
pos_control.set_alt_target_from_climb_rate_ff(climb_rate_cms, G_Dt, false);
|
||||
|
@ -59,7 +59,7 @@ void Copter::land_gps_run()
|
||||
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -119,7 +119,7 @@ void Copter::land_gps_run()
|
||||
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// pause 4 seconds before beginning land descent
|
||||
float cmb_rate;
|
||||
@ -164,7 +164,7 @@ void Copter::land_nogps_run()
|
||||
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -185,7 +185,7 @@ void Copter::land_nogps_run()
|
||||
}
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// pause 4 seconds before beginning land descent
|
||||
float cmb_rate;
|
||||
|
@ -93,7 +93,7 @@ void Copter::loiter_run()
|
||||
wp_nav.init_loiter_target();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -139,7 +139,7 @@ void Copter::loiter_run()
|
||||
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// update altitude target and call position controller
|
||||
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
||||
@ -152,7 +152,7 @@ void Copter::loiter_run()
|
||||
wp_nav.init_loiter_target();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
@ -167,7 +167,7 @@ void Copter::loiter_run()
|
||||
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// run altitude controller
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
|
@ -507,7 +507,7 @@ void Copter::poshold_run()
|
||||
poshold.pitch = constrain_int16(poshold.pitch, -aparm.angle_max, aparm.angle_max);
|
||||
|
||||
// update attitude controller targets
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(poshold.roll, poshold.pitch, target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(poshold.roll, poshold.pitch, target_yaw_rate);
|
||||
|
||||
// throttle control
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
|
@ -143,7 +143,7 @@ void Copter::rtl_climb_return_run()
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
@ -172,10 +172,10 @@ void Copter::rtl_climb_return_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
}
|
||||
|
||||
// check if we've completed this stage of RTL
|
||||
@ -205,7 +205,7 @@ void Copter::rtl_loiterathome_run()
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// reset attitude control targets
|
||||
@ -234,10 +234,10 @@ void Copter::rtl_loiterathome_run()
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
}else{
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
attitude_control.euler_angle_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(),true);
|
||||
}
|
||||
|
||||
// check if we've completed this stage of RTL
|
||||
@ -281,7 +281,7 @@ void Copter::rtl_descent_run()
|
||||
if(!ap.auto_armed || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -317,7 +317,7 @@ void Copter::rtl_descent_run()
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// check if we've reached within 20cm of final altitude
|
||||
rtl_state_complete = fabsf(pv_alt_above_origin(g.rtl_alt_final) - inertial_nav.get_altitude()) < 20.0f;
|
||||
@ -349,7 +349,7 @@ void Copter::rtl_land_run()
|
||||
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
||||
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
@ -409,7 +409,7 @@ void Copter::rtl_land_run()
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);
|
||||
|
||||
// check if we've completed this stage of RTL
|
||||
rtl_state_complete = ap.land_complete;
|
||||
|
@ -97,7 +97,7 @@ void Copter::sport_run()
|
||||
}else{
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.rate_ef_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
|
||||
attitude_control.euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
|
||||
|
||||
// call throttle controller
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
|
@ -51,7 +51,7 @@ void Copter::stabilize_run()
|
||||
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());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
|
@ -63,7 +63,7 @@ void Copter::heli_stabilize_run()
|
||||
pilot_throttle_scaled = input_manager.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());
|
||||
attitude_control.euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
||||
// output pilot's throttle - note that TradHeli does not used angle-boost
|
||||
attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
|
||||
|
Loading…
Reference in New Issue
Block a user