2015-11-24 04:24:04 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#include <AP_Motors/AP_Motors.h>
|
|
|
|
#include <AC_PID/AC_PID.h>
|
|
|
|
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
|
|
|
|
#include <AP_InertialNav/AP_InertialNav.h>
|
|
|
|
#include <AC_AttitudeControl/AC_PosControl.h>
|
2015-12-26 04:51:05 -04:00
|
|
|
#include <AC_WPNav/AC_WPNav.h>
|
2015-11-24 04:24:04 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
QuadPlane specific functionality
|
|
|
|
*/
|
|
|
|
class QuadPlane
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
friend class Plane;
|
|
|
|
QuadPlane(AP_AHRS_NavEKF &_ahrs);
|
|
|
|
|
|
|
|
// var_info for holding Parameter information
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2015-12-26 06:40:40 -04:00
|
|
|
void control_run(void);
|
|
|
|
void control_auto(const Location &loc);
|
|
|
|
bool init_mode(void);
|
2016-01-06 03:17:08 -04:00
|
|
|
bool setup(void);
|
2015-11-24 04:24:04 -04:00
|
|
|
|
|
|
|
// update transition handling
|
|
|
|
void update(void);
|
|
|
|
|
|
|
|
// set motor arming
|
|
|
|
void set_armed(bool armed);
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
// is VTOL available?
|
|
|
|
bool available(void) const {
|
|
|
|
return initialised;
|
|
|
|
}
|
|
|
|
|
2016-01-01 02:36:41 -04:00
|
|
|
// is quadplane assisting?
|
|
|
|
bool in_assisted_flight(void) const {
|
|
|
|
return available() && assisted_flight;
|
|
|
|
}
|
|
|
|
|
2015-12-26 06:40:40 -04:00
|
|
|
bool handle_do_vtol_transition(const mavlink_command_long_t &packet);
|
|
|
|
|
2016-01-01 05:42:10 -04:00
|
|
|
bool do_vtol_takeoff(const AP_Mission::Mission_Command& cmd);
|
|
|
|
bool do_vtol_land(const AP_Mission::Mission_Command& cmd);
|
|
|
|
bool verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd);
|
2016-01-02 02:55:56 -04:00
|
|
|
bool verify_vtol_land(const AP_Mission::Mission_Command &cmd);
|
2016-01-01 06:39:36 -04:00
|
|
|
bool in_vtol_auto(void);
|
2016-02-20 05:20:27 -04:00
|
|
|
bool in_vtol_mode(void);
|
2016-01-01 06:39:36 -04:00
|
|
|
|
|
|
|
// vtol help for is_flying()
|
|
|
|
bool is_flying(void);
|
2016-01-03 06:38:51 -04:00
|
|
|
|
|
|
|
// return current throttle as a percentate
|
|
|
|
uint8_t throttle_percentage(void) const {
|
|
|
|
return last_throttle * 0.1f;
|
|
|
|
}
|
2016-01-01 05:42:10 -04:00
|
|
|
|
2015-11-24 04:24:04 -04:00
|
|
|
private:
|
|
|
|
AP_AHRS_NavEKF &ahrs;
|
|
|
|
AP_Vehicle::MultiCopter aparm;
|
2016-02-29 06:46:27 -04:00
|
|
|
AC_PID pid_rate_roll {0.25, 0.1, 0.004, 2000, 20, 0.02};
|
|
|
|
AC_PID pid_rate_pitch{0.25, 0.1, 0.004, 2000, 20, 0.02};
|
2015-11-24 04:24:04 -04:00
|
|
|
AC_PID pid_rate_yaw {0.15, 0.1, 0.004, 2000, 20, 0.02};
|
|
|
|
AC_P p_stabilize_roll{4.5};
|
|
|
|
AC_P p_stabilize_pitch{4.5};
|
|
|
|
AC_P p_stabilize_yaw{4.5};
|
|
|
|
|
|
|
|
AP_InertialNav_NavEKF inertial_nav{ahrs};
|
|
|
|
|
|
|
|
AC_P p_pos_xy{1};
|
|
|
|
AC_P p_alt_hold{1};
|
|
|
|
AC_P p_vel_z{5};
|
2016-02-29 06:46:27 -04:00
|
|
|
AC_PID pid_accel_z{0.3, 1, 0, 800, 20, 0.02};
|
2015-11-24 04:24:04 -04:00
|
|
|
AC_PI_2D pi_vel_xy{1.0, 0.5, 1000, 5, 0.02};
|
2016-02-07 20:00:19 -04:00
|
|
|
|
|
|
|
AP_Int8 frame_class;
|
|
|
|
AP_Int8 frame_type;
|
2015-11-24 04:24:04 -04:00
|
|
|
|
2016-02-07 20:00:19 -04:00
|
|
|
AP_MotorsMulticopter *motors;
|
2015-12-26 06:40:40 -04:00
|
|
|
AC_AttitudeControl_Multi *attitude_control;
|
|
|
|
AC_PosControl *pos_control;
|
|
|
|
AC_WPNav *wp_nav;
|
2015-12-26 04:51:05 -04:00
|
|
|
|
2015-12-26 03:45:42 -04:00
|
|
|
// maximum vertical velocity the pilot may request
|
|
|
|
AP_Int16 pilot_velocity_z_max;
|
|
|
|
|
|
|
|
// vertical acceleration the pilot may request
|
|
|
|
AP_Int16 pilot_accel_z;
|
|
|
|
|
2015-11-24 04:24:04 -04:00
|
|
|
// update transition handling
|
|
|
|
void update_transition(void);
|
2015-12-26 04:27:13 -04:00
|
|
|
|
|
|
|
// hold hover (for transition)
|
|
|
|
void hold_hover(float target_climb_rate);
|
|
|
|
|
|
|
|
// hold stabilize (for transition)
|
|
|
|
void hold_stabilize(float throttle_in);
|
2015-12-26 04:51:05 -04:00
|
|
|
|
2016-01-09 18:42:46 -04:00
|
|
|
// get pilot desired yaw rate in cd/s
|
|
|
|
float get_pilot_input_yaw_rate_cds(void);
|
2015-12-26 04:51:05 -04:00
|
|
|
|
2016-01-09 18:42:46 -04:00
|
|
|
// get overall desired yaw rate in cd/s
|
|
|
|
float get_desired_yaw_rate_cds(void);
|
|
|
|
|
2015-12-26 04:51:05 -04:00
|
|
|
// get desired climb rate in cm/s
|
|
|
|
float get_pilot_desired_climb_rate_cms(void);
|
2015-12-26 05:13:20 -04:00
|
|
|
|
|
|
|
// initialise throttle_wait when entering mode
|
|
|
|
void init_throttle_wait();
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
// main entry points for VTOL flight modes
|
|
|
|
void init_stabilize(void);
|
|
|
|
void control_stabilize(void);
|
|
|
|
|
|
|
|
void init_hover(void);
|
|
|
|
void control_hover(void);
|
|
|
|
|
|
|
|
void init_loiter(void);
|
2016-03-09 03:20:41 -04:00
|
|
|
void init_land(void);
|
2015-12-26 06:40:40 -04:00
|
|
|
void control_loiter(void);
|
2016-03-09 03:20:41 -04:00
|
|
|
void check_land_complete(void);
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
float assist_climb_rate_cms(void);
|
|
|
|
|
|
|
|
// calculate desired yaw rate for assistance
|
2016-01-09 18:42:46 -04:00
|
|
|
float desired_auto_yaw_rate_cds(void);
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
bool should_relax(void);
|
2016-02-07 20:00:19 -04:00
|
|
|
|
|
|
|
// setup correct aux channels for frame class
|
|
|
|
void setup_default_channels(uint8_t num_motors);
|
2015-11-24 04:24:04 -04:00
|
|
|
|
|
|
|
AP_Int16 transition_time_ms;
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
AP_Int16 rc_speed;
|
|
|
|
|
|
|
|
// min and max PWM for throttle
|
|
|
|
AP_Int16 thr_min_pwm;
|
|
|
|
AP_Int16 thr_max_pwm;
|
2016-01-06 00:19:57 -04:00
|
|
|
AP_Int16 throttle_mid;
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
// speed below which quad assistance is given
|
|
|
|
AP_Float assist_speed;
|
2016-01-02 00:25:49 -04:00
|
|
|
|
|
|
|
// maximum yaw rate in degrees/second
|
|
|
|
AP_Float yaw_rate_max;
|
2016-01-02 02:55:56 -04:00
|
|
|
|
|
|
|
// landing speed in cm/s
|
|
|
|
AP_Int16 land_speed_cms;
|
|
|
|
|
|
|
|
// alt to switch to QLAND_FINAL
|
|
|
|
AP_Float land_final_alt;
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
AP_Int8 enable;
|
2016-01-15 01:49:49 -04:00
|
|
|
AP_Int8 transition_pitch_max;
|
|
|
|
|
2015-12-26 06:40:40 -04:00
|
|
|
bool initialised;
|
2015-11-24 04:24:04 -04:00
|
|
|
|
2015-12-26 04:51:05 -04:00
|
|
|
// timer start for transition
|
|
|
|
uint32_t transition_start_ms;
|
2015-11-24 04:24:04 -04:00
|
|
|
|
2015-12-26 06:40:40 -04:00
|
|
|
Location last_auto_target;
|
|
|
|
|
2015-11-24 04:24:04 -04:00
|
|
|
// last throttle value when active
|
2015-12-26 04:27:13 -04:00
|
|
|
float last_throttle;
|
2015-11-24 04:24:04 -04:00
|
|
|
|
|
|
|
const float smoothing_gain = 6;
|
2015-12-26 04:27:13 -04:00
|
|
|
|
|
|
|
// true if we have reached the airspeed threshold for transition
|
|
|
|
enum {
|
|
|
|
TRANSITION_AIRSPEED_WAIT,
|
|
|
|
TRANSITION_TIMER,
|
|
|
|
TRANSITION_DONE
|
|
|
|
} transition_state;
|
2015-12-26 05:13:20 -04:00
|
|
|
|
|
|
|
// true when waiting for pilot throttle
|
|
|
|
bool throttle_wait;
|
2015-12-26 06:40:40 -04:00
|
|
|
|
|
|
|
// true when quad is assisting a fixed wing mode
|
|
|
|
bool assisted_flight;
|
|
|
|
|
|
|
|
// time when motors reached lower limit
|
|
|
|
uint32_t motors_lower_limit_start_ms;
|
2016-01-01 03:18:53 -04:00
|
|
|
|
|
|
|
// time we last set the loiter target
|
|
|
|
uint32_t last_loiter_ms;
|
2016-01-01 05:42:10 -04:00
|
|
|
|
2016-01-02 02:55:56 -04:00
|
|
|
enum {
|
|
|
|
QLAND_POSITION,
|
|
|
|
QLAND_DESCEND,
|
|
|
|
QLAND_FINAL,
|
|
|
|
QLAND_COMPLETE
|
|
|
|
} land_state;
|
2016-01-15 01:49:49 -04:00
|
|
|
int32_t land_yaw_cd;
|
|
|
|
float land_wp_proportion;
|
2016-02-07 20:00:19 -04:00
|
|
|
|
|
|
|
enum frame_class {
|
|
|
|
FRAME_CLASS_QUAD=0,
|
|
|
|
FRAME_CLASS_HEXA=1,
|
|
|
|
FRAME_CLASS_OCTA=2,
|
2016-03-12 19:05:10 -04:00
|
|
|
FRAME_CLASS_OCTAQUAD=3,
|
2016-02-07 20:00:19 -04:00
|
|
|
};
|
2016-03-12 19:05:10 -04:00
|
|
|
|
|
|
|
struct {
|
|
|
|
bool running;
|
|
|
|
uint32_t start_ms; // system time the motor test began
|
|
|
|
uint32_t timeout_ms = 0; // test will timeout this many milliseconds after the motor_test_start_ms
|
|
|
|
uint8_t seq = 0; // motor sequence number of motor being tested
|
|
|
|
uint8_t throttle_type = 0; // motor throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through)
|
|
|
|
uint16_t throttle_value = 0; // throttle to be sent to motor, value depends upon it's type
|
|
|
|
} motor_test;
|
|
|
|
|
|
|
|
public:
|
|
|
|
void motor_test_output();
|
|
|
|
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,
|
|
|
|
uint16_t throttle_value, float timeout_sec);
|
|
|
|
private:
|
|
|
|
void motor_test_stop();
|
2015-11-24 04:24:04 -04:00
|
|
|
};
|