Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.h
9693 views
#pragma once12/// @file AC_AttitudeControl_TVBS.h3/// @brief ArduCopter attitude control library45#include "AC_AttitudeControl_Multi.h"67class AC_AttitudeControl_TS : public AC_AttitudeControl_Multi8{9public:10using AC_AttitudeControl_Multi::AC_AttitudeControl_Multi;1112// empty destructor to suppress compiler warning13virtual ~AC_AttitudeControl_TS() {}1415// Ensure attitude controllers have zero errors to relax rate controller output16// Relax only the roll and yaw rate controllers if exclude_pitch is true17virtual void relax_attitude_controllers(bool exclude_pitch) override;181920// Commands a body-frame roll angle (in centidegrees), an euler pitch angle (in centidegrees), and a yaw rate (in centidegrees/s).21// See input_euler_rate_yaw_euler_angle_pitch_bf_roll_rad() for full details.22virtual void input_euler_rate_yaw_euler_angle_pitch_bf_roll_cd(bool plane_controls, float body_roll_cd, float euler_pitch_cd, float euler_yaw_rate_cds) override;2324// Commands a body-frame roll angle (in radians), an euler pitch angle (in radians), and a yaw rate (in radians/s).25// Used by tailsitter quadplanes. Optionally swaps roll and yaw effects as pitch nears 90° if plane_controls is true.26virtual void input_euler_rate_yaw_euler_angle_pitch_bf_roll_rad(bool plane_controls, float body_roll_rad, float euler_pitch_rad, float euler_yaw_rate_rads) override;27};282930