ardupilot/ArduPlane/tiltrotor.h

118 lines
3.2 KiB
C++

/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <AP_Param/AP_Param.h>
#include "transition.h"
class QuadPlane;
class AP_MotorsMulticopter;
class Tiltrotor_Transition;
class Tiltrotor
{
friend class QuadPlane;
friend class Plane;
friend class Tiltrotor_Transition;
public:
Tiltrotor(QuadPlane& _quadplane, AP_MotorsMulticopter*& _motors);
bool enabled() const { return (enable > 0) && setup_complete;}
void setup();
void slew(float tilt);
void binary_slew(bool forward);
void update();
void continuous_update();
void binary_update();
void vectoring();
void bicopter_output();
void tilt_compensate_angle(float *thrust, uint8_t num_motors, float non_tilted_mul, float tilted_mul);
void tilt_compensate(float *thrust, uint8_t num_motors);
bool is_motor_tilting(uint8_t motor) const {
return (((uint8_t)tilt_mask.get()) & (1U<<motor));
}
bool fully_fwd() const;
float tilt_max_change(bool up, bool in_flap_range = false) const;
float get_fully_forward_tilt() const;
float get_forward_flight_tilt() const;
// update yaw target for tiltrotor transition
void update_yaw_target();
bool is_vectored() const { return enabled() && _is_vectored; }
bool motors_active() const { return enabled() && _motors_active; }
AP_Int8 enable;
AP_Int16 tilt_mask;
AP_Int16 max_rate_up_dps;
AP_Int16 max_rate_down_dps;
AP_Int8 max_angle_deg;
AP_Int8 type;
AP_Float tilt_yaw_angle;
AP_Float fixed_angle;
AP_Float fixed_gain;
AP_Float flap_angle_deg;
float current_tilt;
float current_throttle;
bool _motors_active:1;
float transition_yaw_cd;
uint32_t transition_yaw_set_ms;
bool _is_vectored;
// types of tilt mechanisms
enum {TILT_TYPE_CONTINUOUS =0,
TILT_TYPE_BINARY =1,
TILT_TYPE_VECTORED_YAW =2,
TILT_TYPE_BICOPTER =3
};
static const struct AP_Param::GroupInfo var_info[];
private:
bool setup_complete;
// refences for convenience
QuadPlane& quadplane;
AP_MotorsMulticopter*& motors;
Tiltrotor_Transition* transition;
};
// Transition for separate left thrust quadplanes
class Tiltrotor_Transition : public SLT_Transition
{
friend class Tiltrotor;
public:
Tiltrotor_Transition(QuadPlane& _quadplane, AP_MotorsMulticopter*& _motors, Tiltrotor& _tiltrotor):SLT_Transition(_quadplane, _motors), tiltrotor(_tiltrotor) {};
bool update_yaw_target(float& yaw_target_cd) override;
bool show_vtol_view() const override;
private:
Tiltrotor& tiltrotor;
};