2021-09-04 19:55:25 -03:00
|
|
|
/*
|
|
|
|
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>
|
2021-09-17 20:28:07 -03:00
|
|
|
#include "transition.h"
|
|
|
|
|
2021-09-04 19:55:25 -03:00
|
|
|
class QuadPlane;
|
|
|
|
class AP_MotorsMulticopter;
|
2021-09-17 20:28:07 -03:00
|
|
|
class Tiltrotor_Transition;
|
2021-09-04 19:55:25 -03:00
|
|
|
class Tiltrotor
|
|
|
|
{
|
|
|
|
friend class QuadPlane;
|
|
|
|
friend class Plane;
|
2021-09-17 20:28:07 -03:00
|
|
|
friend class Tiltrotor_Transition;
|
2021-09-04 19:55:25 -03:00
|
|
|
public:
|
|
|
|
|
|
|
|
Tiltrotor(QuadPlane& _quadplane, AP_MotorsMulticopter*& _motors);
|
|
|
|
|
2021-09-17 20:28:07 -03:00
|
|
|
bool enabled() const { return (enable > 0) && setup_complete;}
|
2021-09-04 19:55:25 -03:00
|
|
|
|
|
|
|
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);
|
2022-01-08 22:47:59 -04:00
|
|
|
bool tilt_over_max_angle(void) const;
|
2021-09-04 19:55:25 -03:00
|
|
|
|
|
|
|
bool is_motor_tilting(uint8_t motor) const {
|
2023-02-25 13:13:51 -04:00
|
|
|
return tilt_mask.get() & (1U<<motor);
|
2021-09-04 19:55:25 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool fully_fwd() const;
|
2022-03-04 17:23:04 -04:00
|
|
|
bool fully_up() const;
|
2021-11-06 15:54:02 -03:00
|
|
|
float tilt_max_change(bool up, bool in_flap_range = false) const;
|
|
|
|
float get_fully_forward_tilt() const;
|
|
|
|
float get_forward_flight_tilt() const;
|
2021-09-04 19:55:25 -03:00
|
|
|
|
|
|
|
// update yaw target for tiltrotor transition
|
|
|
|
void update_yaw_target();
|
|
|
|
|
|
|
|
bool is_vectored() const { return enabled() && _is_vectored; }
|
|
|
|
|
2021-11-21 22:18:19 -04:00
|
|
|
bool has_fw_motor() const { return _have_fw_motor; }
|
|
|
|
|
|
|
|
bool has_vtol_motor() const { return _have_vtol_motor; }
|
|
|
|
|
2021-09-04 19:55:25 -03:00
|
|
|
bool motors_active() const { return enabled() && _motors_active; }
|
|
|
|
|
2021-11-26 18:53:24 -04:00
|
|
|
// true if the tilts have completed slewing
|
|
|
|
// always return true if not enabled or not a continuous type
|
|
|
|
bool tilt_angle_achieved() const { return !enabled() || (type != TILT_TYPE_CONTINUOUS) || angle_achieved; }
|
|
|
|
|
2021-09-04 19:55:25 -03:00
|
|
|
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;
|
2021-11-06 15:54:02 -03:00
|
|
|
AP_Float flap_angle_deg;
|
2021-09-04 19:55:25 -03:00
|
|
|
|
|
|
|
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:
|
|
|
|
|
2021-09-17 20:28:07 -03:00
|
|
|
bool setup_complete;
|
|
|
|
|
2021-11-21 22:18:19 -04:00
|
|
|
// true if a fixed forward motor is setup
|
|
|
|
bool _have_fw_motor;
|
|
|
|
|
|
|
|
// true if all motors tilt with no fixed VTOL motor
|
|
|
|
bool _have_vtol_motor;
|
|
|
|
|
2021-11-26 18:53:24 -04:00
|
|
|
// true if the current tilt angle is equal to the desired
|
|
|
|
// with slow tilt rates the tilt angle can lag
|
|
|
|
bool angle_achieved;
|
|
|
|
|
2021-09-04 19:55:25 -03:00
|
|
|
// refences for convenience
|
|
|
|
QuadPlane& quadplane;
|
|
|
|
AP_MotorsMulticopter*& motors;
|
|
|
|
|
2021-09-17 20:28:07 -03:00
|
|
|
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;
|
|
|
|
|
2021-09-04 19:55:25 -03:00
|
|
|
};
|