Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/mode_acro.cpp
Views: 1798
#include "mode.h"1#include "Plane.h"23bool ModeAcro::_enter()4{5acro_state.locked_roll = false;6acro_state.locked_pitch = false;7IGNORE_RETURN(ahrs.get_quaternion(acro_state.q));8return true;9}1011void ModeAcro::update()12{13// handle locked/unlocked control14if (acro_state.locked_roll) {15plane.nav_roll_cd = acro_state.locked_roll_err;16} else {17plane.nav_roll_cd = ahrs.roll_sensor;18}19if (acro_state.locked_pitch) {20plane.nav_pitch_cd = acro_state.locked_pitch_cd;21} else {22plane.nav_pitch_cd = ahrs.pitch_sensor;23}24}2526void ModeAcro::run()27{28output_pilot_throttle();2930if (plane.g.acro_locking == 2 && plane.g.acro_yaw_rate > 0 &&31plane.yawController.rate_control_enabled()) {32// we can do 3D acro locking33stabilize_quaternion();34return;35}3637// Normal acro38stabilize();39}4041/*42this is the ACRO mode stabilization function. It does rate43stabilization on roll and pitch axes44*/45void ModeAcro::stabilize()46{47const float speed_scaler = plane.get_speed_scaler();48const float rexpo = plane.roll_in_expo(true);49const float pexpo = plane.pitch_in_expo(true);50float roll_rate = (rexpo/SERVO_MAX) * plane.g.acro_roll_rate;51float pitch_rate = (pexpo/SERVO_MAX) * plane.g.acro_pitch_rate;5253IGNORE_RETURN(ahrs.get_quaternion(acro_state.q));5455/*56check for special roll handling near the pitch poles57*/58if (plane.g.acro_locking && is_zero(roll_rate)) {59/*60we have no roll stick input, so we will enter "roll locked"61mode, and hold the roll we had when the stick was released62*/63if (!acro_state.locked_roll) {64acro_state.locked_roll = true;65acro_state.locked_roll_err = 0;66} else {67acro_state.locked_roll_err += ahrs.get_gyro().x * plane.G_Dt;68}69int32_t roll_error_cd = -ToDeg(acro_state.locked_roll_err)*100;70plane.nav_roll_cd = ahrs.roll_sensor + roll_error_cd;71// try to reduce the integrated angular error to zero. We set72// 'stabilize' to true, which disables the roll integrator73SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_servo_out(roll_error_cd,74speed_scaler,75true, false));76} else {77/*78aileron stick is non-zero, use pure rate control until the79user releases the stick80*/81acro_state.locked_roll = false;82SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_rate_out(roll_rate, speed_scaler));83}8485if (plane.g.acro_locking && is_zero(pitch_rate)) {86/*87user has zero pitch stick input, so we lock pitch at the88point they release the stick89*/90if (!acro_state.locked_pitch) {91acro_state.locked_pitch = true;92acro_state.locked_pitch_cd = ahrs.pitch_sensor;93}94// try to hold the locked pitch. Note that we have the pitch95// integrator enabled, which helps with inverted flight96plane.nav_pitch_cd = acro_state.locked_pitch_cd;97SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitchController.get_servo_out(plane.nav_pitch_cd - ahrs.pitch_sensor,98speed_scaler,99false, false));100} else {101/*102user has non-zero pitch input, use a pure rate controller103*/104acro_state.locked_pitch = false;105SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitchController.get_rate_out(pitch_rate, speed_scaler));106}107108float rudder_output;109if (plane.g.acro_yaw_rate > 0 && plane.yawController.rate_control_enabled()) {110// user has asked for yaw rate control with yaw rate scaled by ACRO_YAW_RATE111const float rudd_expo = plane.rudder_in_expo(true);112const float yaw_rate = (rudd_expo/SERVO_MAX) * plane.g.acro_yaw_rate;113rudder_output = plane.yawController.get_rate_out(yaw_rate, speed_scaler, false);114} else if (plane.flight_option_enabled(FlightOptions::ACRO_YAW_DAMPER)) {115// use yaw controller116rudder_output = plane.calc_nav_yaw_coordinated();117} else {118/*119manual rudder120*/121rudder_output = plane.rudder_input();122}123124output_rudder_and_steering(rudder_output);125126}127128/*129quaternion based acro stabilization with continuous locking. Enabled with ACRO_LOCKING=2130*/131void ModeAcro::stabilize_quaternion()132{133const float speed_scaler = plane.get_speed_scaler();134auto &q = acro_state.q;135const float rexpo = plane.roll_in_expo(true);136const float pexpo = plane.pitch_in_expo(true);137const float yexpo = plane.rudder_in_expo(true);138139// get pilot desired rates140float roll_rate = (rexpo/SERVO_MAX) * plane.g.acro_roll_rate;141float pitch_rate = (pexpo/SERVO_MAX) * plane.g.acro_pitch_rate;142float yaw_rate = (yexpo/SERVO_MAX) * plane.g.acro_yaw_rate;143bool roll_active = !is_zero(roll_rate);144bool pitch_active = !is_zero(pitch_rate);145bool yaw_active = !is_zero(yaw_rate);146147// integrate target attitude148Vector3f r{ float(radians(roll_rate)), float(radians(pitch_rate)), float(radians(yaw_rate)) };149r *= plane.G_Dt;150q.rotate_fast(r);151q.normalize();152153// fill in target roll/pitch for GCS/logs154plane.nav_roll_cd = degrees(q.get_euler_roll())*100;155plane.nav_pitch_cd = degrees(q.get_euler_pitch())*100;156157// get AHRS attitude158Quaternion ahrs_q;159IGNORE_RETURN(ahrs.get_quaternion(ahrs_q));160161// zero target if not flying, no stick input and zero throttle162if (is_zero(plane.get_throttle_input()) &&163!plane.is_flying() &&164is_zero(roll_rate) &&165is_zero(pitch_rate) &&166is_zero(yaw_rate)) {167// cope with sitting on the ground with neutral sticks, no throttle168q = ahrs_q;169}170171// get error in attitude172Quaternion error_quat = ahrs_q.inverse() * q;173Vector3f error_angle1;174error_quat.to_axis_angle(error_angle1);175176// don't let too much error build up, limit to 0.2s177const float max_error_t = 0.2;178float max_err_roll_rad = radians(plane.g.acro_roll_rate*max_error_t);179float max_err_pitch_rad = radians(plane.g.acro_pitch_rate*max_error_t);180float max_err_yaw_rad = radians(plane.g.acro_yaw_rate*max_error_t);181182if (!roll_active && acro_state.roll_active_last) {183max_err_roll_rad = 0;184}185if (!pitch_active && acro_state.pitch_active_last) {186max_err_pitch_rad = 0;187}188if (!yaw_active && acro_state.yaw_active_last) {189max_err_yaw_rad = 0;190}191192Vector3f desired_rates = error_angle1;193desired_rates.x = constrain_float(desired_rates.x, -max_err_roll_rad, max_err_roll_rad);194desired_rates.y = constrain_float(desired_rates.y, -max_err_pitch_rad, max_err_pitch_rad);195desired_rates.z = constrain_float(desired_rates.z, -max_err_yaw_rad, max_err_yaw_rad);196197// correct target based on max error198q.rotate_fast(desired_rates - error_angle1);199q.normalize();200201// convert to desired body rates202desired_rates.x /= plane.rollController.tau();203desired_rates.y /= plane.pitchController.tau();204desired_rates.z /= plane.pitchController.tau(); // no yaw tau parameter, use pitch205206desired_rates *= degrees(1.0);207208if (roll_active) {209desired_rates.x = roll_rate;210}211if (pitch_active) {212desired_rates.y = pitch_rate;213}214if (yaw_active) {215desired_rates.z = yaw_rate;216}217218// call to rate controllers219SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_rate_out(desired_rates.x, speed_scaler));220SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitchController.get_rate_out(desired_rates.y, speed_scaler));221output_rudder_and_steering(plane.yawController.get_rate_out(desired_rates.z, speed_scaler, false));222223acro_state.roll_active_last = roll_active;224acro_state.pitch_active_last = pitch_active;225acro_state.yaw_active_last = yaw_active;226}227228229