mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
cc2c631d23
move tailsitter body-frame roll input method to new subclass override relax_attitude_controllers in AttitudeControl_TS
22 lines
836 B
C++
22 lines
836 B
C++
#pragma once
|
|
|
|
/// @file AC_AttitudeControl_TVBS.h
|
|
/// @brief ArduCopter attitude control library
|
|
|
|
#include "AC_AttitudeControl_Multi.h"
|
|
|
|
|
|
class AC_AttitudeControl_TS : public AC_AttitudeControl_Multi
|
|
{
|
|
public:
|
|
AC_AttitudeControl_TS(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt);
|
|
|
|
// empty destructor to suppress compiler warning
|
|
virtual ~AC_AttitudeControl_TS() {}
|
|
|
|
// Ensure attitude controllers have zero errors to relax rate controller output
|
|
// Relax only the roll and yaw rate controllers if exclude_pitch is true
|
|
virtual void relax_attitude_controllers(bool exclude_pitch) override;
|
|
virtual void 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) override;
|
|
};
|