vtol_att avoid unnecessary work and delete unused

This commit is contained in:
Daniel Agar
2017-12-31 20:23:51 -05:00
committed by Lorenz Meier
parent d3a220f807
commit 66f614435f
12 changed files with 178 additions and 565 deletions

View File

@@ -4,11 +4,9 @@ uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_FW = 1
uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2
uint8 VEHICLE_VTOL_STATE_MC = 3
uint8 VEHICLE_VTOL_STATE_FW = 4
uint8 VEHICLE_VTOL_STATE_EXTERNAL = 5
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
bool vtol_in_trans_mode
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool vtol_transition_failsafe # vtol in transition failsafe mode
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode
float32 airspeed_tot # Estimated airspeed over control surfaces

View File

@@ -1567,7 +1567,6 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- VTOL VEHICLE STATUS --- */
if(copy_if_updated(ORB_ID(vtol_vehicle_status), &subs.vtol_status_sub, &buf.vtol_status)) {
log_msg.msg_type = LOG_VTOL_MSG;
log_msg.body.log_VTOL.airspeed_tot = buf.vtol_status.airspeed_tot;
log_msg.body.log_VTOL.rw_mode = buf.vtol_status.vtol_in_rw_mode;
log_msg.body.log_VTOL.trans_mode = buf.vtol_status.vtol_in_trans_mode;
log_msg.body.log_VTOL.failsafe_mode = buf.vtol_status.vtol_transition_failsafe;

View File

@@ -466,7 +466,6 @@ struct log_ENCD_s {
/* --- VTOL - VTOL VEHICLE STATUS */
#define LOG_VTOL_MSG 43
struct log_VTOL_s {
float airspeed_tot;
uint8_t rw_mode;
uint8_t trans_mode;
uint8_t failsafe_mode;

View File

@@ -50,13 +50,10 @@
Tailsitter::Tailsitter(VtolAttitudeControl *attc) :
VtolType(attc),
_airspeed_tot(0.0f),
_min_front_trans_dur(0.5f),
_thrust_transition_start(0.0f),
_yaw_transition(0.0f),
_pitch_transition_start(0.0f),
_loop_perf(perf_alloc(PC_ELAPSED, "vtol_att_control-tailsitter")),
_nonfinite_input_perf(perf_alloc(PC_COUNT, "vtol att control-tailsitter nonfinite input"))
_pitch_transition_start(0.0f)
{
_vtol_schedule.flight_mode = MC_MODE;
_vtol_schedule.transition_start = 0;
@@ -133,7 +130,6 @@ void Tailsitter::update_vtol_state()
if (!_attc->is_fixed_wing_requested()) {
switch (_vtol_schedule.flight_mode) { // user switchig to MC mode
case MC_MODE:
break;
@@ -334,9 +330,6 @@ void Tailsitter::update_transition_state()
}
_mc_roll_weight = math::constrain(_mc_roll_weight, 0.0f, 1.0f);
_mc_yaw_weight = math::constrain(_mc_yaw_weight, 0.0f, 1.0f);
_mc_pitch_weight = math::constrain(_mc_pitch_weight, 0.0f, 1.0f);
@@ -358,58 +351,6 @@ void Tailsitter::waiting_on_tecs()
_v_att_sp->thrust = _thrust_transition;
}
void Tailsitter::calc_tot_airspeed()
{
float airspeed = math::max(1.0f, _airspeed->indicated_airspeed_m_s); // prevent numerical drama
// calculate momentary power of one engine
float P = _batt_status->voltage_filtered_v * _batt_status->current_a / _params->vtol_motor_count;
P = math::constrain(P, 1.0f, _params->power_max);
// calculate prop efficiency
float power_factor = 1.0f - P * _params->prop_eff / _params->power_max;
float eta = (1.0f / (1 + expf(-0.4f * power_factor * airspeed)) - 0.5f) * 2.0f;
eta = math::constrain(eta, 0.001f, 1.0f); // live on the safe side
// calculate induced airspeed by propeller
float v_ind = (airspeed / eta - airspeed) * 2.0f;
// calculate total airspeed
float airspeed_raw = airspeed + v_ind;
// apply low-pass filter
_airspeed_tot = _params->arsp_lp_gain * (_airspeed_tot - airspeed_raw) + airspeed_raw;
}
void Tailsitter::scale_mc_output()
{
// scale around tuning airspeed
float airspeed;
calc_tot_airspeed(); // estimate air velocity seen by elevons
// if airspeed is not updating, we assume the normal average speed
if (bool nonfinite = !PX4_ISFINITE(_airspeed->indicated_airspeed_m_s) ||
hrt_elapsed_time(&_airspeed->timestamp) > 1e6) {
airspeed = _params->mc_airspeed_trim;
if (nonfinite) {
perf_count(_nonfinite_input_perf);
}
} else {
airspeed = _airspeed_tot;
airspeed = math::constrain(airspeed, _params->mc_airspeed_min, _params->mc_airspeed_max);
}
_vtol_vehicle_status->airspeed_tot = airspeed; // save value for logging
/*
* For scaling our actuators using anything less than the min (close to stall)
* speed doesn't make any sense - its the strongest reasonable deflection we
* want to do in flight and its the baseline a human pilot would choose.
*
* Forcing the scaling to this value allows reasonable handheld tests.
*/
float airspeed_scaling = _params->mc_airspeed_trim / ((airspeed < _params->mc_airspeed_min) ? _params->mc_airspeed_min :
airspeed);
_actuators_mc_in->control[1] = math::constrain(_actuators_mc_in->control[1] * airspeed_scaling * airspeed_scaling,
-1.0f, 1.0f);
}
void Tailsitter::update_mc_state()
{
VtolType::update_mc_state();
@@ -504,9 +445,5 @@ void Tailsitter::fill_actuator_outputs()
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] =
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
break;
case EXTERNAL:
// not yet implemented, we are switching brute force at the moment
break;
}
}

View File

@@ -96,8 +96,6 @@ private:
hrt_abstime transition_start; /**< absoulte time at which front transition started */
} _vtol_schedule;
float _airspeed_tot; /** speed estimation for propwash controlled surfaces */
/** not sure about it yet ?! **/
float _min_front_trans_dur; /**< min possible time in which rotors are rotated into the first position */
@@ -105,20 +103,6 @@ private:
float _yaw_transition; // yaw angle in which transition will take place
float _pitch_transition_start; // pitch angle at the start of transition (tailsitter)
/** should this anouncement stay? **/
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
/**
* Speed estimation for propwash controlled surfaces.
*/
void calc_tot_airspeed();
/** is this one still needed? */
void scale_mc_output();
/**
* Update parameters.
*/

View File

@@ -39,8 +39,6 @@
* @author David Vorsin <davidvorsin@gmail.com>
*/
#include <systemlib/param/param.h>
/**
* Duration of front transition phase 2
*

View File

@@ -38,8 +38,6 @@
* @author Roman Bapst <roman@px4.io>
*/
#include <systemlib/param/param.h>
/**
* Position of tilt servo in mc mode
*

File diff suppressed because it is too large Load Diff

View File

@@ -59,13 +59,10 @@
#include <drivers/drv_pwm_output.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/tecs_status.h>
@@ -80,7 +77,6 @@
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vtol_vehicle_status.h>
#include <uORB/uORB.h>
#include "tiltrotor.h"
#include "tailsitter.h"
@@ -101,104 +97,90 @@ public:
bool is_fixed_wing_requested();
void abort_front_transition(const char *reason);
struct vehicle_attitude_s *get_att() {return &_v_att;}
struct vehicle_attitude_setpoint_s *get_att_sp() {return &_v_att_sp;}
struct vehicle_attitude_setpoint_s *get_mc_virtual_att_sp() {return &_mc_virtual_att_sp;}
struct vehicle_attitude_setpoint_s *get_fw_virtual_att_sp() {return &_fw_virtual_att_sp;}
struct vehicle_rates_setpoint_s *get_rates_sp() {return &_v_rates_sp;}
struct vehicle_rates_setpoint_s *get_mc_virtual_rates_sp() {return &_mc_virtual_v_rates_sp;}
struct vehicle_rates_setpoint_s *get_fw_virtual_rates_sp() {return &_fw_virtual_v_rates_sp;}
struct manual_control_setpoint_s *get_manual_control_sp() {return &_manual_control_sp;}
struct vehicle_control_mode_s *get_control_mode() {return &_v_control_mode;}
struct vtol_vehicle_status_s *get_vtol_vehicle_status() {return &_vtol_vehicle_status;}
struct actuator_controls_s *get_actuators_fw_in() {return &_actuators_fw_in;}
struct actuator_controls_s *get_actuators_mc_in() {return &_actuators_mc_in;}
struct actuator_controls_s *get_actuators_out0() {return &_actuators_out_0;}
struct actuator_controls_s *get_actuators_out1() {return &_actuators_out_1;}
struct actuator_controls_s *get_actuators_mc_in() {return &_actuators_mc_in;}
struct actuator_controls_s *get_actuators_fw_in() {return &_actuators_fw_in;}
struct airspeed_s *get_airspeed() {return &_airspeed;}
struct position_setpoint_triplet_s *get_pos_sp_triplet() {return &_pos_sp_triplet;}
struct tecs_status_s *get_tecs_status() {return &_tecs_status;}
struct vehicle_attitude_s *get_att() {return &_v_att;}
struct vehicle_attitude_setpoint_s *get_att_sp() {return &_v_att_sp;}
struct vehicle_attitude_setpoint_s *get_fw_virtual_att_sp() {return &_fw_virtual_att_sp;}
struct vehicle_attitude_setpoint_s *get_mc_virtual_att_sp() {return &_mc_virtual_att_sp;}
struct vehicle_control_mode_s *get_control_mode() {return &_v_control_mode;}
struct vehicle_land_detected_s *get_land_detected() {return &_land_detected;}
struct vehicle_local_position_s *get_local_pos() {return &_local_pos;}
struct vehicle_local_position_setpoint_s *get_local_pos_sp() {return &_local_pos_sp;}
struct position_setpoint_triplet_s *get_pos_sp_triplet() {return &_pos_sp_triplet;}
struct airspeed_s *get_airspeed() {return &_airspeed;}
struct battery_status_s *get_batt_status() {return &_batt_status;}
struct tecs_status_s *get_tecs_status() {return &_tecs_status;}
struct vehicle_land_detected_s *get_land_detected() {return &_land_detected;}
struct vtol_vehicle_status_s *get_vtol_vehicle_status() {return &_vtol_vehicle_status;}
struct Params *get_params() {return &_params;}
private:
//******************flags & handlers******************************************************
bool _task_should_exit;
int _control_task; //task handle for VTOL attitude controller
orb_advert_t _mavlink_log_pub; // mavlink log uORB handle
bool _task_should_exit{false};
int _control_task{-1}; //task handle for VTOL attitude controller
/* handlers for subscriptions */
int _v_att_sub; //vehicle attitude subscription
int _v_att_sp_sub; //vehicle attitude setpoint subscription
int _mc_virtual_att_sp_sub;
int _fw_virtual_att_sp_sub;
int _mc_virtual_v_rates_sp_sub; //vehicle rates setpoint subscription
int _fw_virtual_v_rates_sp_sub; //vehicle rates setpoint subscription
int _v_control_mode_sub; //vehicle control mode subscription
int _params_sub; //parameter updates subscription
int _manual_control_sp_sub; //manual control setpoint subscription
int _local_pos_sub; // sensor subscription
int _local_pos_sp_sub; // setpoint subscription
int _pos_sp_triplet_sub; // local position setpoint subscription
int _airspeed_sub; // airspeed subscription
int _battery_status_sub; // battery status subscription
int _vehicle_cmd_sub;
int _tecs_status_sub;
int _land_detected_sub;
int _actuator_inputs_mc; //topic on which the mc_att_controller publishes actuator inputs
int _actuator_inputs_fw; //topic on which the fw_att_controller publishes actuator inputs
int _actuator_inputs_fw{-1}; //topic on which the fw_att_controller publishes actuator inputs
int _actuator_inputs_mc{-1}; //topic on which the mc_att_controller publishes actuator inputs
int _airspeed_sub{-1}; // airspeed subscription
int _fw_virtual_att_sp_sub{-1};
int _fw_virtual_v_rates_sp_sub{-1}; //vehicle rates setpoint subscription
int _land_detected_sub{-1};
int _local_pos_sp_sub{-1}; // setpoint subscription
int _local_pos_sub{-1}; // sensor subscription
int _manual_control_sp_sub{-1}; //manual control setpoint subscription
int _mc_virtual_att_sp_sub{-1};
int _mc_virtual_v_rates_sp_sub{-1}; //vehicle rates setpoint subscription
int _params_sub{-1}; //parameter updates subscription
int _pos_sp_triplet_sub{-1}; // local position setpoint subscription
int _tecs_status_sub{-1};
int _v_att_sp_sub{-1}; //vehicle attitude setpoint subscription
int _v_att_sub{-1}; //vehicle attitude subscription
int _v_control_mode_sub{-1}; //vehicle control mode subscription
int _vehicle_cmd_sub{-1};
//handlers for publishers
orb_advert_t _actuators_0_pub; //input for the mixer (roll,pitch,yaw,thrust)
orb_advert_t _actuators_1_pub;
orb_advert_t _vtol_vehicle_status_pub;
orb_advert_t _v_rates_sp_pub;
orb_advert_t _v_att_sp_pub;
orb_advert_t _v_cmd_ack_pub;
orb_advert_t _actuators_0_pub{nullptr}; //input for the mixer (roll,pitch,yaw,thrust)
orb_advert_t _mavlink_log_pub{nullptr}; // mavlink log uORB handle
orb_advert_t _v_att_sp_pub{nullptr};
orb_advert_t _v_cmd_ack_pub{nullptr};
orb_advert_t _v_rates_sp_pub{nullptr};
orb_advert_t _vtol_vehicle_status_pub{nullptr};
orb_advert_t _actuators_1_pub{nullptr};
//*******************data containers***********************************************************
struct vehicle_attitude_s _v_att; //vehicle attitude
struct vehicle_attitude_setpoint_s _v_att_sp; //vehicle attitude setpoint
struct vehicle_attitude_setpoint_s _mc_virtual_att_sp; // virtual mc attitude setpoint
struct vehicle_attitude_setpoint_s _fw_virtual_att_sp; // virtual fw attitude setpoint
struct vehicle_rates_setpoint_s _v_rates_sp; //vehicle rates setpoint
struct vehicle_rates_setpoint_s _mc_virtual_v_rates_sp; // virtual mc vehicle rates setpoint
struct vehicle_rates_setpoint_s _fw_virtual_v_rates_sp; // virtual fw vehicle rates setpoint
struct manual_control_setpoint_s _manual_control_sp; //manual control setpoint
struct vehicle_control_mode_s _v_control_mode; //vehicle control mode
struct vtol_vehicle_status_s _vtol_vehicle_status;
struct actuator_controls_s _actuators_out_0; //actuator controls going to the mc mixer
struct actuator_controls_s _actuators_out_1; //actuator controls going to the fw mixer (used for elevons)
struct actuator_controls_s _actuators_mc_in; //actuator controls from mc_att_control
struct actuator_controls_s _actuators_fw_in; //actuator controls from fw_att_control
struct vehicle_local_position_s _local_pos;
struct vehicle_local_position_setpoint_s _local_pos_sp;
struct position_setpoint_triplet_s _pos_sp_triplet;
struct airspeed_s _airspeed; // airspeed
struct battery_status_s _batt_status; // battery status
struct vehicle_command_s _vehicle_cmd;
struct tecs_status_s _tecs_status;
struct vehicle_land_detected_s _land_detected;
Params _params; // struct holding the parameters
vehicle_attitude_setpoint_s _v_att_sp{}; //vehicle attitude setpoint
vehicle_attitude_setpoint_s _fw_virtual_att_sp{}; // virtual fw attitude setpoint
vehicle_attitude_setpoint_s _mc_virtual_att_sp{}; // virtual mc attitude setpoint
actuator_controls_s _actuators_fw_in{}; //actuator controls from fw_att_control
actuator_controls_s _actuators_mc_in{}; //actuator controls from mc_att_control
actuator_controls_s _actuators_out_0{}; //actuator controls going to the mc mixer
actuator_controls_s _actuators_out_1{}; //actuator controls going to the fw mixer (used for elevons)
airspeed_s _airspeed{}; // airspeed
manual_control_setpoint_s _manual_control_sp{}; //manual control setpoint
position_setpoint_triplet_s _pos_sp_triplet{};
tecs_status_s _tecs_status{};
vehicle_attitude_s _v_att{}; //vehicle attitude
vehicle_command_s _vehicle_cmd{};
vehicle_control_mode_s _v_control_mode{}; //vehicle control mode
vehicle_land_detected_s _land_detected{};
vehicle_local_position_s _local_pos{};
vehicle_local_position_setpoint_s _local_pos_sp{};
vtol_vehicle_status_s _vtol_vehicle_status{};
Params _params{}; // struct holding the parameters
struct {
param_t idle_pwm_mc;
param_t vtol_motor_count;
param_t vtol_fw_permanent_stab;
param_t mc_airspeed_min;
param_t mc_airspeed_trim;
param_t mc_airspeed_max;
param_t fw_pitch_trim;
param_t power_max;
param_t prop_eff;
param_t arsp_lp_gain;
param_t vtol_type;
param_t elevons_mc_lock;
param_t fw_min_alt;
@@ -210,45 +192,42 @@ private:
param_t wv_takeoff;
param_t wv_loiter;
param_t wv_land;
} _params_handles;
} _params_handles{};
/* for multicopters it is usual to have a non-zero idle speed of the engines
* for fixed wings we want to have an idle speed of zero since we do not want
* to waste energy when gliding. */
int _transition_command;
bool _abort_front_transition;
int _transition_command{vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC};
bool _abort_front_transition{false};
VtolType *_vtol_type = nullptr; // base class for different vtol types
VtolType *_vtol_type{nullptr}; // base class for different vtol types
//*****************Member functions***********************************************************************
void task_main(); //main task
static void task_main_trampoline(int argc, char *argv[]); //Shim for calling task_main from task_create.
void land_detected_poll();
void tecs_status_poll();
void vehicle_attitude_poll(); //Check for attitude updates.
void vehicle_cmd_poll();
void vehicle_control_mode_poll(); //Check for changes in vehicle control mode.
void vehicle_manual_poll(); //Check for changes in manual inputs.
void mc_virtual_att_sp_poll();
void fw_virtual_att_sp_poll();
void actuator_controls_mc_poll(); //Check for changes in mc_attitude_control output
void actuator_controls_fw_poll(); //Check for changes in fw_attitude_control output
void vehicle_rates_sp_mc_poll();
void vehicle_rates_sp_fw_poll();
void vehicle_local_pos_poll(); // Check for changes in sensor values
void vehicle_local_pos_sp_poll(); // Check for changes in setpoint values
void actuator_controls_mc_poll(); //Check for changes in mc_attitude_control output
void fw_virtual_att_sp_poll();
void mc_virtual_att_sp_poll();
void pos_sp_triplet_poll(); // Check for changes in position setpoint values
void vehicle_airspeed_poll(); // Check for changes in airspeed
void vehicle_attitude_setpoint_poll(); //Check for attitude setpoint updates.
void vehicle_attitude_poll(); //Check for attitude updates.
void vehicle_battery_poll(); // Check for battery updates
void vehicle_cmd_poll();
void tecs_status_poll();
void land_detected_poll();
void parameters_update_poll(); //Check if parameters have changed
void vehicle_local_pos_poll(); // Check for changes in sensor values
void vehicle_local_pos_sp_poll(); // Check for changes in setpoint values
int parameters_update(); //Update local paraemter cache
void fill_mc_att_rates_sp();
void fill_fw_att_rates_sp();
void handle_command();
void publish_att_sp();
};
#endif

View File

@@ -62,48 +62,6 @@ PARAM_DEFINE_INT32(VT_MOT_COUNT, 0);
*/
PARAM_DEFINE_INT32(VT_IDLE_PWM_MC, 900);
/**
* Minimum airspeed in multicopter mode
*
* This is the minimum speed of the air flowing over the control surfaces.
*
* @unit m/s
* @min 0.0
* @max 30.0
* @increment 0.5
* @decimal 2
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN, 10.0f);
/**
* Maximum airspeed in multicopter mode
*
* This is the maximum speed of the air flowing over the control surfaces.
*
* @unit m/s
* @min 0.0
* @max 30.0
* @increment 0.5
* @decimal 2
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX, 30.0f);
/**
* Trim airspeed when in multicopter mode
*
* This is the airflow over the control surfaces for which no airspeed scaling is applied in multicopter mode.
*
* @unit m/s
* @min 0.0
* @max 30.0
* @increment 0.5
* @decimal 2
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM, 10.0f);
/**
* Permanent stabilization in fw mode
*
@@ -128,47 +86,6 @@ PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0);
*/
PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM, 0.0f);
/**
* Motor max power
*
* Indicates the maximum power the motor is able to produce. Used to calculate
* propeller efficiency map.
*
* @unit W
* @min 1
* @max 10000
* @increment 1
* @decimal 0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_POWER_MAX, 120.0f);
/**
* Propeller efficiency parameter
*
* Influences propeller efficiency at different power settings. Should be tuned beforehand.
*
* @min 0.0
* @max 1.0
* @increment 0.01
* @decimal 3
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_PROP_EFF, 0.0f);
/**
* Total airspeed estimate low-pass filter gain
*
* Gain for tuning the low-pass filter for the total airspeed estimate
*
* @min 0.0
* @max 1.0
* @increment 0.01
* @decimal 3
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN, 0.3f);
/**
* VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)
*

View File

@@ -54,10 +54,6 @@ VtolType::VtolType(VtolAttitudeControl *att_controller) :
_v_att_sp = _attc->get_att_sp();
_mc_virtual_att_sp = _attc->get_mc_virtual_att_sp();
_fw_virtual_att_sp = _attc->get_fw_virtual_att_sp();
_v_rates_sp = _attc->get_rates_sp();
_mc_virtual_v_rates_sp = _attc->get_mc_virtual_rates_sp();
_fw_virtual_v_rates_sp = _attc->get_fw_virtual_rates_sp();
_manual_control_sp = _attc->get_manual_control_sp();
_v_control_mode = _attc->get_control_mode();
_vtol_vehicle_status = _attc->get_vtol_vehicle_status();
_actuators_out_0 = _attc->get_actuators_out0();
@@ -67,7 +63,6 @@ VtolType::VtolType(VtolAttitudeControl *att_controller) :
_local_pos = _attc->get_local_pos();
_local_pos_sp = _attc->get_local_pos_sp();
_airspeed = _attc->get_airspeed();
_batt_status = _attc->get_batt_status();
_tecs_status = _attc->get_tecs_status();
_land_detected = _attc->get_land_detected();
_params = _attc->get_params();

View File

@@ -49,13 +49,7 @@
struct Params {
int32_t idle_pwm_mc; // pwm value for idle in mc mode
int32_t vtol_motor_count; // number of motors
float mc_airspeed_min; // min airspeed in multicoper mode (including prop-wash)
float mc_airspeed_trim; // trim airspeed in multicopter mode
float mc_airspeed_max; // max airpseed in multicopter mode
float fw_pitch_trim; // trim for neutral elevon position in fw mode
float power_max; // maximum power of one engine
float prop_eff; // factor to calculate prop efficiency
float arsp_lp_gain; // total airspeed estimate low pass gain
int32_t vtol_type;
int32_t elevons_mc_lock; // lock elevons in multicopter mode
float fw_min_alt; // minimum relative altitude for FW mode (QuadChute)
@@ -74,8 +68,7 @@ enum mode {
TRANSITION_TO_FW = 1,
TRANSITION_TO_MC = 2,
ROTARY_WING = 3,
FIXED_WING = 4,
EXTERNAL = 5
FIXED_WING = 4
};
enum vtol_type {
@@ -116,11 +109,6 @@ public:
*/
virtual void update_fw_state();
/**
* Update external state.
*/
virtual void update_external_state() {}
/**
* Write control values to actuator output topics.
*/
@@ -157,10 +145,6 @@ protected:
struct vehicle_attitude_setpoint_s *_v_att_sp; //vehicle attitude setpoint
struct vehicle_attitude_setpoint_s *_mc_virtual_att_sp; // virtual mc attitude setpoint
struct vehicle_attitude_setpoint_s *_fw_virtual_att_sp; // virtual fw attitude setpoint
struct vehicle_rates_setpoint_s *_v_rates_sp; //vehicle rates setpoint
struct vehicle_rates_setpoint_s *_mc_virtual_v_rates_sp; // virtual mc vehicle rates setpoint
struct vehicle_rates_setpoint_s *_fw_virtual_v_rates_sp; // virtual fw vehicle rates setpoint
struct manual_control_setpoint_s *_manual_control_sp; //manual control setpoint
struct vehicle_control_mode_s *_v_control_mode; //vehicle control mode
struct vtol_vehicle_status_s *_vtol_vehicle_status;
struct actuator_controls_s *_actuators_out_0; //actuator controls going to the mc mixer
@@ -170,7 +154,6 @@ protected:
struct vehicle_local_position_s *_local_pos;
struct vehicle_local_position_setpoint_s *_local_pos_sp;
struct airspeed_s *_airspeed; // airspeed
struct battery_status_s *_batt_status; // battery status
struct tecs_status_s *_tecs_status;
struct vehicle_land_detected_s *_land_detected;