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/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.1314This class inherits from AC_AttitudeControl_Multi and provides functionality15specific to tailsitter quadplanes.161) "body-frame" roll control mode for all tailsitters172) a relax_attitude_controller method needed for coping with vectored tailsitters18*/19#include "AC_AttitudeControl_TS.h"2021void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch)22{23// If exclude_pitch: relax roll and yaw rate controller outputs only,24// leaving pitch controller active to let TVBS motors tilt up while in throttle_wait25if (exclude_pitch) {26// Get the current attitude quaternion27Quaternion current_attitude;28_ahrs.get_quat_body_to_ned(current_attitude);2930Vector3f current_eulers;31current_attitude.to_euler(current_eulers.x, current_eulers.y, current_eulers.z);3233// set target attitude to zero pitch with (approximate) current roll and yaw34// by rotating the current_attitude quaternion by the error in desired pitch35Quaternion pitch_rotation;36pitch_rotation.from_axis_angle(Vector3f(0, -1, 0), current_eulers.y);37_attitude_target = current_attitude * pitch_rotation;38_attitude_target.normalize();39_attitude_target.to_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);40_attitude_ang_error = current_attitude.inverse() * _attitude_target;4142// Initialize the roll and yaw angular rate variables to the current rate43_ang_vel_target = _ahrs.get_gyro();44ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);45_ang_vel_body.x = _ahrs.get_gyro().x;46_ang_vel_body.z = _ahrs.get_gyro().z;4748// Reset the roll and yaw I terms49get_rate_roll_pid().reset_I();50get_rate_yaw_pid().reset_I();51} else {52// relax all attitude controllers53AC_AttitudeControl::relax_attitude_controllers();54}55}5657// Command euler yaw rate and pitch angle with roll angle specified in body frame58// (used only by tailsitter quadplanes)59// If plane_controls is true, swap the effects of roll and yaw as euler pitch approaches 90 degrees60void AC_AttitudeControl_TS::input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float body_roll_cd, float euler_pitch_cd, float euler_yaw_rate_cds)61{62// Convert from centidegrees on public interface to radians63float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);64float euler_pitch = radians(constrain_float(euler_pitch_cd * 0.01f, -90.0f, 90.0f));65float body_roll = radians(-body_roll_cd * 0.01f);6667const float cpitch = cosf(euler_pitch);68const float spitch = fabsf(sinf(euler_pitch));6970// Compute attitude error71Quaternion attitude_body;72Quaternion error_quat;73_ahrs.get_quat_body_to_ned(attitude_body);74error_quat = attitude_body.inverse() * _attitude_target;75Vector3f att_error;76error_quat.to_axis_angle(att_error);7778// update heading79float yaw_rate = euler_yaw_rate;80if (plane_controls) {81yaw_rate = (euler_yaw_rate * spitch) + (body_roll * cpitch);82}83// limit yaw error84float yaw_error = fabsf(att_error.z);85float error_ratio = yaw_error / M_PI_2;86if (error_ratio > 1) {87yaw_rate /= (error_ratio * error_ratio);88}89_euler_angle_target.z = wrap_PI(_euler_angle_target.z + yaw_rate * _dt);9091// init attitude target to desired euler yaw and pitch with zero roll92_attitude_target.from_euler(0, euler_pitch, _euler_angle_target.z);9394// apply body-frame yaw/roll (this is roll/yaw for a tailsitter in forward flight)95// rotate body_roll axis by |sin(pitch angle)|96Quaternion bf_roll_Q;97bf_roll_Q.from_axis_angle(Vector3f(0, 0, spitch * body_roll));9899// rotate body_yaw axis by cos(pitch angle)100Quaternion bf_yaw_Q;101if (plane_controls) {102bf_yaw_Q.from_axis_angle(Vector3f(cpitch, 0, 0), euler_yaw_rate);103} else {104bf_yaw_Q.from_axis_angle(Vector3f(-cpitch * body_roll, 0, 0));105}106_attitude_target = _attitude_target * bf_roll_Q * bf_yaw_Q;107108// _euler_angle_target roll and pitch: Note: roll/yaw will be indeterminate when pitch is near +/-90109// These should be used only for logging target eulers, with the caveat noted above.110// Also note that _attitude_target.from_euler() should only be used in special circumstances111// such as when attitude is specified directly in terms of Euler angles.112// _euler_angle_target.x = _attitude_target.get_euler_roll();113// _euler_angle_target.y = euler_pitch;114115// Set rate feedforward requests to zero116_euler_rate_target.zero();117_ang_vel_target.zero();118119// Compute attitude error120error_quat = attitude_body.inverse() * _attitude_target;121error_quat.to_axis_angle(att_error);122123// Compute the angular velocity target from the attitude error124_ang_vel_body = update_ang_vel_target_from_att_error(att_error);125}126127128