forked from Archive/PX4-Autopilot
fix code style of vtol files
This commit is contained in:
parent
6634952a0c
commit
9ef2994134
|
@ -60,7 +60,7 @@ Standard::Standard(VtolAttitudeControl *attc) :
|
|||
_params_handles_standard.pusher_trans = param_find("VT_TRANS_THR");
|
||||
_params_handles_standard.airspeed_blend = param_find("VT_ARSP_BLEND");
|
||||
_params_handles_standard.airspeed_trans = param_find("VT_ARSP_TRANS");
|
||||
}
|
||||
}
|
||||
|
||||
Standard::~Standard()
|
||||
{
|
||||
|
@ -98,12 +98,12 @@ Standard::parameters_update()
|
|||
|
||||
void Standard::update_vtol_state()
|
||||
{
|
||||
parameters_update();
|
||||
parameters_update();
|
||||
|
||||
/* After flipping the switch the vehicle will start the pusher (or tractor) motor, picking up
|
||||
* forward speed. After the vehicle has picked up enough speed the rotors shutdown.
|
||||
* forward speed. After the vehicle has picked up enough speed the rotors shutdown.
|
||||
* For the back transition the pusher motor is immediately stopped and rotors reactivated.
|
||||
*/
|
||||
*/
|
||||
|
||||
if (!_attc->is_fixed_wing_requested()) {
|
||||
// the transition to fw mode switch is off
|
||||
|
@ -130,7 +130,7 @@ void Standard::update_vtol_state()
|
|||
} else if (_vtol_schedule.flight_mode == TRANSITION_TO_MC) {
|
||||
// transition to MC mode if transition time has passed
|
||||
if (hrt_elapsed_time(&_vtol_schedule.transition_start) >
|
||||
(_params_standard.back_trans_dur * 1000000.0f)) {
|
||||
(_params_standard.back_trans_dur * 1000000.0f)) {
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
}
|
||||
}
|
||||
|
@ -168,17 +168,19 @@ void Standard::update_vtol_state()
|
|||
}
|
||||
|
||||
// map specific control phases to simple control modes
|
||||
switch(_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
_vtol_mode = ROTARY_WING;
|
||||
break;
|
||||
case FW_MODE:
|
||||
_vtol_mode = FIXED_WING;
|
||||
break;
|
||||
case TRANSITION_TO_FW:
|
||||
case TRANSITION_TO_MC:
|
||||
_vtol_mode = TRANSITION;
|
||||
break;
|
||||
switch (_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
_vtol_mode = ROTARY_WING;
|
||||
break;
|
||||
|
||||
case FW_MODE:
|
||||
_vtol_mode = FIXED_WING;
|
||||
break;
|
||||
|
||||
case TRANSITION_TO_FW:
|
||||
case TRANSITION_TO_MC:
|
||||
_vtol_mode = TRANSITION;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -188,18 +190,21 @@ void Standard::update_transition_state()
|
|||
if (_params_standard.front_trans_dur <= 0.0f) {
|
||||
// just set the final target throttle value
|
||||
_pusher_throttle = _params_standard.pusher_trans;
|
||||
|
||||
} else if (_pusher_throttle <= _params_standard.pusher_trans) {
|
||||
// ramp up throttle to the target throttle value
|
||||
_pusher_throttle = _params_standard.pusher_trans *
|
||||
(float)hrt_elapsed_time(&_vtol_schedule.transition_start) / (_params_standard.front_trans_dur * 1000000.0f);
|
||||
_pusher_throttle = _params_standard.pusher_trans *
|
||||
(float)hrt_elapsed_time(&_vtol_schedule.transition_start) / (_params_standard.front_trans_dur * 1000000.0f);
|
||||
}
|
||||
|
||||
// do blending of mc and fw controls if a blending airspeed has been provided
|
||||
if (_airspeed_trans_blend_margin > 0.0f && _airspeed->true_airspeed_m_s >= _params_standard.airspeed_blend) {
|
||||
float weight = 1.0f - fabsf(_airspeed->true_airspeed_m_s - _params_standard.airspeed_blend) / _airspeed_trans_blend_margin;
|
||||
float weight = 1.0f - fabsf(_airspeed->true_airspeed_m_s - _params_standard.airspeed_blend) /
|
||||
_airspeed_trans_blend_margin;
|
||||
_mc_roll_weight = weight;
|
||||
_mc_pitch_weight = weight;
|
||||
_mc_yaw_weight = weight;
|
||||
|
||||
} else {
|
||||
// at low speeds give full weight to mc
|
||||
_mc_roll_weight = 1.0f;
|
||||
|
@ -210,17 +215,19 @@ void Standard::update_transition_state()
|
|||
} else if (_vtol_schedule.flight_mode == TRANSITION_TO_MC) {
|
||||
// continually increase mc attitude control as we transition back to mc mode
|
||||
if (_params_standard.back_trans_dur > 0.0f) {
|
||||
float weight = (float)hrt_elapsed_time(&_vtol_schedule.transition_start) / (_params_standard.back_trans_dur * 1000000.0f);
|
||||
float weight = (float)hrt_elapsed_time(&_vtol_schedule.transition_start) / (_params_standard.back_trans_dur *
|
||||
1000000.0f);
|
||||
_mc_roll_weight = weight;
|
||||
_mc_pitch_weight = weight;
|
||||
_mc_yaw_weight = weight;
|
||||
|
||||
} else {
|
||||
_mc_roll_weight = 1.0f;
|
||||
_mc_pitch_weight = 1.0f;
|
||||
_mc_yaw_weight = 1.0f;
|
||||
}
|
||||
|
||||
// in fw mode we need the multirotor motors to stop spinning, in backtransition mode we let them spin up again
|
||||
// in fw mode we need the multirotor motors to stop spinning, in backtransition mode we let them spin up again
|
||||
if (_flag_enable_mc_motors) {
|
||||
set_max_mc(2000);
|
||||
set_idle_mc();
|
||||
|
@ -238,15 +245,15 @@ void Standard::update_mc_state()
|
|||
// do nothing
|
||||
}
|
||||
|
||||
void Standard::update_fw_state()
|
||||
void Standard::update_fw_state()
|
||||
{
|
||||
// in fw mode we need the multirotor motors to stop spinning, in backtransition mode we let them spin up again
|
||||
// in fw mode we need the multirotor motors to stop spinning, in backtransition mode we let them spin up again
|
||||
if (!_flag_enable_mc_motors) {
|
||||
set_max_mc(950);
|
||||
set_idle_fw(); // force them to stop, not just idle
|
||||
_flag_enable_mc_motors = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Standard::update_external_state()
|
||||
{
|
||||
|
@ -259,22 +266,31 @@ void Standard::update_external_state()
|
|||
void Standard::fill_actuator_outputs()
|
||||
{
|
||||
/* multirotor controls */
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL] * _mc_roll_weight; // roll
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] = _actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight; // pitch
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW] * _mc_yaw_weight; // yaw
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE]; // throttle
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL]
|
||||
* _mc_roll_weight; // roll
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight; // pitch
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW] *
|
||||
_mc_yaw_weight; // yaw
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE]; // throttle
|
||||
|
||||
/* fixed wing controls */
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = -_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL] * (1 - _mc_roll_weight); //roll
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] = (_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim) * (1 - _mc_pitch_weight); //pitch
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] = _actuators_fw_in->control[actuator_controls_s::INDEX_YAW] * (1 - _mc_yaw_weight); // yaw
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = -_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL]
|
||||
* (1 - _mc_roll_weight); //roll
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
|
||||
(_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim) * (1 - _mc_pitch_weight); //pitch
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] = _actuators_fw_in->control[actuator_controls_s::INDEX_YAW]
|
||||
* (1 - _mc_yaw_weight); // yaw
|
||||
|
||||
// set the fixed wing throttle control
|
||||
if (_vtol_schedule.flight_mode == FW_MODE) {
|
||||
// take the throttle value commanded by the fw controller
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
|
||||
} else {
|
||||
// otherwise we may be ramping up the throttle during the transition to fw mode
|
||||
// otherwise we may be ramping up the throttle during the transition to fw mode
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] = _pusher_throttle;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -31,15 +31,15 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file standard.h
|
||||
* VTOL with fixed multirotor motor configurations (such as quad) and a pusher
|
||||
* (or puller aka tractor) motor for forward flight.
|
||||
*
|
||||
* @author Simon Wilks <simon@uaventure.com>
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file standard.h
|
||||
* VTOL with fixed multirotor motor configurations (such as quad) and a pusher
|
||||
* (or puller aka tractor) motor for forward flight.
|
||||
*
|
||||
* @author Simon Wilks <simon@uaventure.com>
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef STANDARD_H
|
||||
#define STANDARD_H
|
||||
|
@ -52,7 +52,7 @@ class Standard : public VtolType
|
|||
|
||||
public:
|
||||
|
||||
Standard(VtolAttitudeControl * _att_controller);
|
||||
Standard(VtolAttitudeControl *_att_controller);
|
||||
~Standard();
|
||||
|
||||
void update_vtol_state();
|
||||
|
@ -89,7 +89,7 @@ private:
|
|||
struct {
|
||||
vtol_mode flight_mode; // indicates in which mode the vehicle is in
|
||||
hrt_abstime transition_start; // at what time did we start a transition (front- or backtransition)
|
||||
}_vtol_schedule;
|
||||
} _vtol_schedule;
|
||||
|
||||
bool _flag_enable_mc_motors;
|
||||
float _pusher_throttle;
|
||||
|
|
|
@ -31,21 +31,21 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file tailsitter.cpp
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file tailsitter.cpp
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#include "tailsitter.h"
|
||||
#include "vtol_att_control_main.h"
|
||||
#include "tailsitter.h"
|
||||
#include "vtol_att_control_main.h"
|
||||
|
||||
Tailsitter::Tailsitter (VtolAttitudeControl *att_controller) :
|
||||
VtolType(att_controller),
|
||||
_airspeed_tot(0),
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "vtol_att_control-tailsitter")),
|
||||
_nonfinite_input_perf(perf_alloc(PC_COUNT, "vtol att control-tailsitter nonfinite input"))
|
||||
Tailsitter::Tailsitter(VtolAttitudeControl *att_controller) :
|
||||
VtolType(att_controller),
|
||||
_airspeed_tot(0),
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "vtol_att_control-tailsitter")),
|
||||
_nonfinite_input_perf(perf_alloc(PC_COUNT, "vtol att control-tailsitter nonfinite input"))
|
||||
{
|
||||
|
||||
}
|
||||
|
@ -60,6 +60,7 @@ void Tailsitter::update_vtol_state()
|
|||
// simply switch between the two modes
|
||||
if (!_attc->is_fixed_wing_requested()) {
|
||||
_vtol_mode = ROTARY_WING;
|
||||
|
||||
} else {
|
||||
_vtol_mode = FIXED_WING;
|
||||
}
|
||||
|
@ -67,7 +68,7 @@ void Tailsitter::update_vtol_state()
|
|||
|
||||
void Tailsitter::update_mc_state()
|
||||
{
|
||||
if (!flag_idle_mc) {
|
||||
if (!flag_idle_mc) {
|
||||
set_idle_mc();
|
||||
flag_idle_mc = true;
|
||||
}
|
||||
|
@ -91,18 +92,18 @@ void Tailsitter::update_external_state()
|
|||
|
||||
}
|
||||
|
||||
void Tailsitter::calc_tot_airspeed()
|
||||
{
|
||||
void Tailsitter::calc_tot_airspeed()
|
||||
{
|
||||
float airspeed = math::max(1.0f, _airspeed->true_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);
|
||||
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
|
||||
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;
|
||||
float v_ind = (airspeed / eta - airspeed) * 2.0f;
|
||||
// calculate total airspeed
|
||||
float airspeed_raw = airspeed + v_ind;
|
||||
// apply low-pass filter
|
||||
|
@ -115,16 +116,19 @@ 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->true_airspeed_m_s) ||
|
||||
hrt_elapsed_time(&_airspeed->timestamp) > 1e6) {
|
||||
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);
|
||||
airspeed = math::constrain(airspeed, _params->mc_airspeed_min, _params->mc_airspeed_max);
|
||||
}
|
||||
|
||||
_vtol_vehicle_status->airspeed_tot = airspeed; // save value for logging
|
||||
|
@ -135,8 +139,10 @@ Tailsitter::scale_mc_output()
|
|||
*
|
||||
* 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);
|
||||
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);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -144,37 +150,50 @@ Tailsitter::scale_mc_output()
|
|||
*/
|
||||
void Tailsitter::fill_actuator_outputs()
|
||||
{
|
||||
switch(_vtol_mode) {
|
||||
case ROTARY_WING:
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] = _actuators_mc_in->control[actuator_controls_s::INDEX_PITCH];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
switch (_vtol_mode) {
|
||||
case ROTARY_WING:
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
|
||||
if (_params->elevons_mc_lock == 1) {
|
||||
_actuators_out_1->control[0] = 0;
|
||||
_actuators_out_1->control[1] = 0;
|
||||
} else {
|
||||
// NOTE: There is no mistake in the line below, multicopter yaw axis is controlled by elevon roll actuation!
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW]; //roll elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] = _actuators_mc_in->control[actuator_controls_s::INDEX_PITCH]; //pitch elevon
|
||||
}
|
||||
break;
|
||||
case FIXED_WING:
|
||||
// in fixed wing mode we use engines only for providing thrust, no moments are generated
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
if (_params->elevons_mc_lock == 1) {
|
||||
_actuators_out_1->control[0] = 0;
|
||||
_actuators_out_1->control[1] = 0;
|
||||
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = -_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL]; // roll elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] = _actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim; // pitch elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] = _actuators_fw_in->control[actuator_controls_s::INDEX_YAW]; // yaw
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE]; // throttle
|
||||
break;
|
||||
case TRANSITION:
|
||||
case EXTERNAL:
|
||||
// not yet implemented, we are switching brute force at the moment
|
||||
break;
|
||||
} else {
|
||||
// NOTE: There is no mistake in the line below, multicopter yaw axis is controlled by elevon roll actuation!
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_YAW]; //roll elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH]; //pitch elevon
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case FIXED_WING:
|
||||
// in fixed wing mode we use engines only for providing thrust, no moments are generated
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = 0;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] =
|
||||
-_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL]; // roll elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim; // pitch elevon
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_YAW]; // yaw
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE]; // throttle
|
||||
break;
|
||||
|
||||
case TRANSITION:
|
||||
case EXTERNAL:
|
||||
// not yet implemented, we are switching brute force at the moment
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -31,12 +31,12 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file tiltrotor.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file tiltrotor.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef TAILSITTER_H
|
||||
#define TAILSITTER_H
|
||||
|
@ -48,7 +48,7 @@ class Tailsitter : public VtolType
|
|||
{
|
||||
|
||||
public:
|
||||
Tailsitter(VtolAttitudeControl * _att_controller);
|
||||
Tailsitter(VtolAttitudeControl *_att_controller);
|
||||
~Tailsitter();
|
||||
|
||||
void update_vtol_state();
|
||||
|
|
|
@ -44,10 +44,10 @@
|
|||
#define ARSP_YAW_CTRL_DISABLE 7.0f // airspeed at which we stop controlling yaw during a front transition
|
||||
|
||||
Tiltrotor::Tiltrotor(VtolAttitudeControl *attc) :
|
||||
VtolType(attc),
|
||||
_rear_motors(ENABLED),
|
||||
_tilt_control(0.0f),
|
||||
_min_front_trans_dur(0.5f)
|
||||
VtolType(attc),
|
||||
_rear_motors(ENABLED),
|
||||
_tilt_control(0.0f),
|
||||
_min_front_trans_dur(0.5f)
|
||||
{
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
_vtol_schedule.transition_start = 0;
|
||||
|
@ -86,11 +86,11 @@ Tiltrotor::parameters_update()
|
|||
|
||||
/* vtol duration of a front transition */
|
||||
param_get(_params_handles_tiltrotor.front_trans_dur, &v);
|
||||
_params_tiltrotor.front_trans_dur = math::constrain(v,1.0f,5.0f);
|
||||
_params_tiltrotor.front_trans_dur = math::constrain(v, 1.0f, 5.0f);
|
||||
|
||||
/* vtol duration of a back transition */
|
||||
param_get(_params_handles_tiltrotor.back_trans_dur, &v);
|
||||
_params_tiltrotor.back_trans_dur = math::constrain(v,0.0f,5.0f);
|
||||
_params_tiltrotor.back_trans_dur = math::constrain(v, 0.0f, 5.0f);
|
||||
|
||||
/* vtol tilt mechanism position in mc mode */
|
||||
param_get(_params_handles_tiltrotor.tilt_mc, &v);
|
||||
|
@ -123,22 +123,26 @@ Tiltrotor::parameters_update()
|
|||
/* avoid parameters which will lead to zero division in the transition code */
|
||||
_params_tiltrotor.front_trans_dur = math::max(_params_tiltrotor.front_trans_dur, _min_front_trans_dur);
|
||||
|
||||
if ( _params_tiltrotor.airspeed_trans < _params_tiltrotor.airspeed_blend_start + 1.0f ) {
|
||||
if (_params_tiltrotor.airspeed_trans < _params_tiltrotor.airspeed_blend_start + 1.0f) {
|
||||
_params_tiltrotor.airspeed_trans = _params_tiltrotor.airspeed_blend_start + 1.0f;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int Tiltrotor::get_motor_off_channels(int channels) {
|
||||
int Tiltrotor::get_motor_off_channels(int channels)
|
||||
{
|
||||
int channel_bitmap = 0;
|
||||
|
||||
|
||||
int channel;
|
||||
|
||||
for (int i = 0; i < _params->vtol_motor_count; ++i) {
|
||||
channel = channels % 10;
|
||||
|
||||
if (channel == 0) {
|
||||
break;
|
||||
}
|
||||
|
||||
channel_bitmap |= 1 << channel;
|
||||
channels = channels / 10;
|
||||
}
|
||||
|
@ -148,82 +152,98 @@ int Tiltrotor::get_motor_off_channels(int channels) {
|
|||
|
||||
void Tiltrotor::update_vtol_state()
|
||||
{
|
||||
parameters_update();
|
||||
parameters_update();
|
||||
|
||||
/* simple logic using a two way switch to perform transitions.
|
||||
/* simple logic using a two way switch to perform transitions.
|
||||
* after flipping the switch the vehicle will start tilting rotors, picking up
|
||||
* forward speed. After the vehicle has picked up enough speed the rotors are tilted
|
||||
* forward completely. For the backtransition the motors simply rotate back.
|
||||
*/
|
||||
*/
|
||||
|
||||
if (!_attc->is_fixed_wing_requested()) {
|
||||
|
||||
// plane is in multicopter mode
|
||||
switch(_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
break;
|
||||
case FW_MODE:
|
||||
_vtol_schedule.flight_mode = TRANSITION_BACK;
|
||||
_vtol_schedule.transition_start = hrt_absolute_time();
|
||||
break;
|
||||
case TRANSITION_FRONT_P1:
|
||||
// failsafe into multicopter mode
|
||||
switch (_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
break;
|
||||
|
||||
case FW_MODE:
|
||||
_vtol_schedule.flight_mode = TRANSITION_BACK;
|
||||
_vtol_schedule.transition_start = hrt_absolute_time();
|
||||
break;
|
||||
|
||||
case TRANSITION_FRONT_P1:
|
||||
// failsafe into multicopter mode
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
break;
|
||||
|
||||
case TRANSITION_FRONT_P2:
|
||||
// failsafe into multicopter mode
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
break;
|
||||
|
||||
case TRANSITION_BACK:
|
||||
if (_tilt_control <= _params_tiltrotor.tilt_mc) {
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
break;
|
||||
case TRANSITION_FRONT_P2:
|
||||
// failsafe into multicopter mode
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
break;
|
||||
case TRANSITION_BACK:
|
||||
if (_tilt_control <= _params_tiltrotor.tilt_mc) {
|
||||
_vtol_schedule.flight_mode = MC_MODE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
switch(_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
// initialise a front transition
|
||||
_vtol_schedule.flight_mode = TRANSITION_FRONT_P1;
|
||||
switch (_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
// initialise a front transition
|
||||
_vtol_schedule.flight_mode = TRANSITION_FRONT_P1;
|
||||
_vtol_schedule.transition_start = hrt_absolute_time();
|
||||
break;
|
||||
|
||||
case FW_MODE:
|
||||
break;
|
||||
|
||||
case TRANSITION_FRONT_P1:
|
||||
|
||||
// check if we have reached airspeed to switch to fw mode
|
||||
if (_airspeed->true_airspeed_m_s >= _params_tiltrotor.airspeed_trans) {
|
||||
_vtol_schedule.flight_mode = TRANSITION_FRONT_P2;
|
||||
_vtol_schedule.transition_start = hrt_absolute_time();
|
||||
break;
|
||||
case FW_MODE:
|
||||
break;
|
||||
case TRANSITION_FRONT_P1:
|
||||
// check if we have reached airspeed to switch to fw mode
|
||||
if (_airspeed->true_airspeed_m_s >= _params_tiltrotor.airspeed_trans) {
|
||||
_vtol_schedule.flight_mode = TRANSITION_FRONT_P2;
|
||||
_vtol_schedule.transition_start = hrt_absolute_time();
|
||||
}
|
||||
break;
|
||||
case TRANSITION_FRONT_P2:
|
||||
// if the rotors have been tilted completely we switch to fw mode
|
||||
if (_tilt_control >= _params_tiltrotor.tilt_fw) {
|
||||
_vtol_schedule.flight_mode = FW_MODE;
|
||||
_tilt_control = _params_tiltrotor.tilt_fw;
|
||||
}
|
||||
break;
|
||||
case TRANSITION_BACK:
|
||||
// failsafe into fixed wing mode
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case TRANSITION_FRONT_P2:
|
||||
|
||||
// if the rotors have been tilted completely we switch to fw mode
|
||||
if (_tilt_control >= _params_tiltrotor.tilt_fw) {
|
||||
_vtol_schedule.flight_mode = FW_MODE;
|
||||
break;
|
||||
_tilt_control = _params_tiltrotor.tilt_fw;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case TRANSITION_BACK:
|
||||
// failsafe into fixed wing mode
|
||||
_vtol_schedule.flight_mode = FW_MODE;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// map tiltrotor specific control phases to simple control modes
|
||||
switch(_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
_vtol_mode = ROTARY_WING;
|
||||
break;
|
||||
case FW_MODE:
|
||||
_vtol_mode = FIXED_WING;
|
||||
break;
|
||||
case TRANSITION_FRONT_P1:
|
||||
case TRANSITION_FRONT_P2:
|
||||
case TRANSITION_BACK:
|
||||
_vtol_mode = TRANSITION;
|
||||
break;
|
||||
switch (_vtol_schedule.flight_mode) {
|
||||
case MC_MODE:
|
||||
_vtol_mode = ROTARY_WING;
|
||||
break;
|
||||
|
||||
case FW_MODE:
|
||||
_vtol_mode = FIXED_WING;
|
||||
break;
|
||||
|
||||
case TRANSITION_FRONT_P1:
|
||||
case TRANSITION_FRONT_P2:
|
||||
case TRANSITION_BACK:
|
||||
_vtol_mode = TRANSITION;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -248,7 +268,7 @@ void Tiltrotor::update_mc_state()
|
|||
_mc_yaw_weight = 1.0f;
|
||||
}
|
||||
|
||||
void Tiltrotor::update_fw_state()
|
||||
void Tiltrotor::update_fw_state()
|
||||
{
|
||||
// make sure motors are tilted forward
|
||||
_tilt_control = _params_tiltrotor.tilt_fw;
|
||||
|
@ -276,15 +296,18 @@ void Tiltrotor::update_transition_state()
|
|||
if (_rear_motors != ENABLED) {
|
||||
set_rear_motor_state(ENABLED);
|
||||
}
|
||||
|
||||
// tilt rotors forward up to certain angle
|
||||
if (_tilt_control <= _params_tiltrotor.tilt_transition ) {
|
||||
if (_tilt_control <= _params_tiltrotor.tilt_transition) {
|
||||
_tilt_control = _params_tiltrotor.tilt_mc +
|
||||
fabsf(_params_tiltrotor.tilt_transition - _params_tiltrotor.tilt_mc) * (float)hrt_elapsed_time(&_vtol_schedule.transition_start)/(_params_tiltrotor.front_trans_dur * 1000000.0f);
|
||||
fabsf(_params_tiltrotor.tilt_transition - _params_tiltrotor.tilt_mc) * (float)hrt_elapsed_time(
|
||||
&_vtol_schedule.transition_start) / (_params_tiltrotor.front_trans_dur * 1000000.0f);
|
||||
}
|
||||
|
||||
// do blending of mc and fw controls
|
||||
if (_airspeed->true_airspeed_m_s >= _params_tiltrotor.airspeed_blend_start) {
|
||||
_mc_roll_weight = 0.0f;
|
||||
|
||||
} else {
|
||||
// at low speeds give full weight to mc
|
||||
_mc_roll_weight = 1.0f;
|
||||
|
@ -292,6 +315,7 @@ void Tiltrotor::update_transition_state()
|
|||
|
||||
// disable mc yaw control once the plane has picked up speed
|
||||
_mc_yaw_weight = 1.0f;
|
||||
|
||||
if (_airspeed->true_airspeed_m_s > ARSP_YAW_CTRL_DISABLE) {
|
||||
_mc_yaw_weight = 0.0f;
|
||||
}
|
||||
|
@ -299,8 +323,10 @@ void Tiltrotor::update_transition_state()
|
|||
} else if (_vtol_schedule.flight_mode == TRANSITION_FRONT_P2) {
|
||||
// the plane is ready to go into fixed wing mode, tilt the rotors forward completely
|
||||
_tilt_control = _params_tiltrotor.tilt_transition +
|
||||
fabsf(_params_tiltrotor.tilt_fw - _params_tiltrotor.tilt_transition) * (float)hrt_elapsed_time(&_vtol_schedule.transition_start)/(_params_tiltrotor.front_trans_dur_p2 * 1000000.0f);
|
||||
fabsf(_params_tiltrotor.tilt_fw - _params_tiltrotor.tilt_transition) * (float)hrt_elapsed_time(
|
||||
&_vtol_schedule.transition_start) / (_params_tiltrotor.front_trans_dur_p2 * 1000000.0f);
|
||||
_mc_roll_weight = 0.0f;
|
||||
|
||||
} else if (_vtol_schedule.flight_mode == TRANSITION_BACK) {
|
||||
if (_rear_motors != IDLE) {
|
||||
set_rear_motor_state(IDLE);
|
||||
|
@ -310,10 +336,12 @@ void Tiltrotor::update_transition_state()
|
|||
set_idle_mc();
|
||||
flag_idle_mc = true;
|
||||
}
|
||||
|
||||
// tilt rotors back
|
||||
if (_tilt_control > _params_tiltrotor.tilt_mc) {
|
||||
_tilt_control = _params_tiltrotor.tilt_fw -
|
||||
fabsf(_params_tiltrotor.tilt_fw - _params_tiltrotor.tilt_mc) * (float)hrt_elapsed_time(&_vtol_schedule.transition_start)/(_params_tiltrotor.back_trans_dur * 1000000.0f);
|
||||
fabsf(_params_tiltrotor.tilt_fw - _params_tiltrotor.tilt_mc) * (float)hrt_elapsed_time(
|
||||
&_vtol_schedule.transition_start) / (_params_tiltrotor.back_trans_dur * 1000000.0f);
|
||||
}
|
||||
|
||||
// set zero throttle for backtransition otherwise unwanted moments will be created
|
||||
|
@ -337,19 +365,28 @@ void Tiltrotor::update_external_state()
|
|||
*/
|
||||
void Tiltrotor::fill_actuator_outputs()
|
||||
{
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL] * _mc_roll_weight;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] = _actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW] * _mc_yaw_weight;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL]
|
||||
* _mc_roll_weight;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW] *
|
||||
_mc_yaw_weight;
|
||||
|
||||
if (_vtol_schedule.flight_mode == FW_MODE) {
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];
|
||||
|
||||
} else {
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = _actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];;
|
||||
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
|
||||
_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];;
|
||||
}
|
||||
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = -_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL] * (1 - _mc_roll_weight);
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] = (_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim) *(1 - _mc_pitch_weight);
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] = _actuators_fw_in->control[actuator_controls_s::INDEX_YAW] * (1 - _mc_yaw_weight); // yaw
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] = -_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL]
|
||||
* (1 - _mc_roll_weight);
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
|
||||
(_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH] + _params->fw_pitch_trim) * (1 - _mc_pitch_weight);
|
||||
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] = _actuators_fw_in->control[actuator_controls_s::INDEX_YAW]
|
||||
* (1 - _mc_yaw_weight); // yaw
|
||||
_actuators_out_1->control[4] = _tilt_control;
|
||||
}
|
||||
|
||||
|
@ -358,23 +395,26 @@ void Tiltrotor::fill_actuator_outputs()
|
|||
* Set state of rear motors.
|
||||
*/
|
||||
|
||||
void Tiltrotor::set_rear_motor_state(rear_motor_state state) {
|
||||
void Tiltrotor::set_rear_motor_state(rear_motor_state state)
|
||||
{
|
||||
int pwm_value = PWM_DEFAULT_MAX;
|
||||
|
||||
// map desired rear rotor state to max allowed pwm signal
|
||||
switch (state) {
|
||||
case ENABLED:
|
||||
pwm_value = PWM_DEFAULT_MAX;
|
||||
_rear_motors = ENABLED;
|
||||
break;
|
||||
case DISABLED:
|
||||
pwm_value = PWM_LOWEST_MAX;
|
||||
_rear_motors = DISABLED;
|
||||
break;
|
||||
case IDLE:
|
||||
pwm_value = _params->idle_pwm_mc;
|
||||
_rear_motors = IDLE;
|
||||
break;
|
||||
case ENABLED:
|
||||
pwm_value = PWM_DEFAULT_MAX;
|
||||
_rear_motors = ENABLED;
|
||||
break;
|
||||
|
||||
case DISABLED:
|
||||
pwm_value = PWM_LOWEST_MAX;
|
||||
_rear_motors = DISABLED;
|
||||
break;
|
||||
|
||||
case IDLE:
|
||||
pwm_value = _params->idle_pwm_mc;
|
||||
_rear_motors = IDLE;
|
||||
break;
|
||||
}
|
||||
|
||||
int ret;
|
||||
|
@ -391,9 +431,11 @@ void Tiltrotor::set_rear_motor_state(rear_motor_state state) {
|
|||
for (int i = 0; i < _params->vtol_motor_count; i++) {
|
||||
if (is_motor_off_channel(i)) {
|
||||
pwm_values.values[i] = pwm_value;
|
||||
|
||||
} else {
|
||||
pwm_values.values[i] = PWM_DEFAULT_MAX;
|
||||
}
|
||||
|
||||
pwm_values.channel_count = _params->vtol_motor_count;
|
||||
}
|
||||
|
||||
|
@ -404,6 +446,7 @@ void Tiltrotor::set_rear_motor_state(rear_motor_state state) {
|
|||
px4_close(fd);
|
||||
}
|
||||
|
||||
bool Tiltrotor::is_motor_off_channel(const int channel) {
|
||||
bool Tiltrotor::is_motor_off_channel(const int channel)
|
||||
{
|
||||
return (_params_tiltrotor.fw_motors_off >> channel) & 1;
|
||||
}
|
||||
|
|
|
@ -31,12 +31,12 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file tiltrotor.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file tiltrotor.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef TILTROTOR_H
|
||||
#define TILTROTOR_H
|
||||
|
@ -49,7 +49,7 @@ class Tiltrotor : public VtolType
|
|||
|
||||
public:
|
||||
|
||||
Tiltrotor(VtolAttitudeControl * _att_controller);
|
||||
Tiltrotor(VtolAttitudeControl *_att_controller);
|
||||
~Tiltrotor();
|
||||
|
||||
/**
|
||||
|
@ -127,7 +127,7 @@ private:
|
|||
struct {
|
||||
vtol_mode flight_mode; /**< vtol flight mode, defined by enum vtol_mode */
|
||||
hrt_abstime transition_start; /**< absoulte time at which front transition started */
|
||||
}_vtol_schedule;
|
||||
} _vtol_schedule;
|
||||
|
||||
float _tilt_control; /**< actuator value for the tilt servo */
|
||||
|
||||
|
|
|
@ -93,10 +93,10 @@ VtolAttitudeControl::VtolAttitudeControl() :
|
|||
memset(&_actuators_mc_in, 0, sizeof(_actuators_mc_in));
|
||||
memset(&_actuators_fw_in, 0, sizeof(_actuators_fw_in));
|
||||
memset(&_armed, 0, sizeof(_armed));
|
||||
memset(&_local_pos,0,sizeof(_local_pos));
|
||||
memset(&_airspeed,0,sizeof(_airspeed));
|
||||
memset(&_batt_status,0,sizeof(_batt_status));
|
||||
memset(&_vehicle_cmd,0, sizeof(_vehicle_cmd));
|
||||
memset(&_local_pos, 0, sizeof(_local_pos));
|
||||
memset(&_airspeed, 0, sizeof(_airspeed));
|
||||
memset(&_batt_status, 0, sizeof(_batt_status));
|
||||
memset(&_vehicle_cmd, 0, sizeof(_vehicle_cmd));
|
||||
|
||||
_params.idle_pwm_mc = PWM_LOWEST_MIN;
|
||||
_params.vtol_motor_count = 0;
|
||||
|
@ -121,12 +121,15 @@ VtolAttitudeControl::VtolAttitudeControl() :
|
|||
if (_params.vtol_type == 0) {
|
||||
_tailsitter = new Tailsitter(this);
|
||||
_vtol_type = _tailsitter;
|
||||
|
||||
} else if (_params.vtol_type == 1) {
|
||||
_tiltrotor = new Tiltrotor(this);
|
||||
_vtol_type = _tiltrotor;
|
||||
|
||||
} else if (_params.vtol_type == 2) {
|
||||
_standard = new Standard(this);
|
||||
_vtol_type = _standard;
|
||||
|
||||
} else {
|
||||
_task_should_exit = true;
|
||||
}
|
||||
|
@ -258,7 +261,8 @@ void VtolAttitudeControl::vehicle_rates_sp_fw_poll()
|
|||
* Check for airspeed updates.
|
||||
*/
|
||||
void
|
||||
VtolAttitudeControl::vehicle_airspeed_poll() {
|
||||
VtolAttitudeControl::vehicle_airspeed_poll()
|
||||
{
|
||||
bool updated;
|
||||
orb_check(_airspeed_sub, &updated);
|
||||
|
||||
|
@ -271,7 +275,8 @@ VtolAttitudeControl::vehicle_airspeed_poll() {
|
|||
* Check for battery updates.
|
||||
*/
|
||||
void
|
||||
VtolAttitudeControl::vehicle_battery_poll() {
|
||||
VtolAttitudeControl::vehicle_battery_poll()
|
||||
{
|
||||
bool updated;
|
||||
orb_check(_battery_status_sub, &updated);
|
||||
|
||||
|
@ -643,11 +648,11 @@ VtolAttitudeControl::start()
|
|||
|
||||
/* start the task */
|
||||
_control_task = px4_task_spawn_cmd("vtol_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
2048,
|
||||
(px4_main_t)&VtolAttitudeControl::task_main_trampoline,
|
||||
nullptr);
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
2048,
|
||||
(px4_main_t)&VtolAttitudeControl::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
if (_control_task < 0) {
|
||||
PX4_WARN("task start failed");
|
||||
|
@ -705,6 +710,7 @@ int vtol_att_control_main(int argc, char *argv[])
|
|||
} else {
|
||||
PX4_WARN("not running");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -104,24 +104,24 @@ public:
|
|||
int start(); /* start the task and return OK on success */
|
||||
bool is_fixed_wing_requested();
|
||||
|
||||
struct vehicle_attitude_s* get_att () {return &_v_att;}
|
||||
struct vehicle_attitude_setpoint_s* get_att_sp () {return &_v_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_vehicle_status () {return &_vtol_vehicle_status;}
|
||||
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 actuator_armed_s* get_armed () {return &_armed;}
|
||||
struct vehicle_local_position_s* get_local_pos () {return &_local_pos;}
|
||||
struct airspeed_s* get_airspeed () {return &_airspeed;}
|
||||
struct battery_status_s* get_batt_status () {return &_batt_status;}
|
||||
struct vehicle_attitude_s *get_att() {return &_v_att;}
|
||||
struct vehicle_attitude_setpoint_s *get_att_sp() {return &_v_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_vehicle_status() {return &_vtol_vehicle_status;}
|
||||
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 actuator_armed_s *get_armed() {return &_armed;}
|
||||
struct vehicle_local_position_s *get_local_pos() {return &_local_pos;}
|
||||
struct airspeed_s *get_airspeed() {return &_airspeed;}
|
||||
struct battery_status_s *get_batt_status() {return &_batt_status;}
|
||||
|
||||
struct Params* get_params () {return &_params;}
|
||||
struct Params *get_params() {return &_params;}
|
||||
|
||||
|
||||
private:
|
||||
|
@ -189,10 +189,10 @@ private:
|
|||
|
||||
int _transition_command;
|
||||
|
||||
VtolType * _vtol_type; // base class for different vtol types
|
||||
Tiltrotor * _tiltrotor; // tailsitter vtol type
|
||||
Tailsitter * _tailsitter; // tiltrotor vtol type
|
||||
Standard * _standard; // standard vtol type
|
||||
VtolType *_vtol_type; // base class for different vtol types
|
||||
Tiltrotor *_tiltrotor; // tailsitter vtol type
|
||||
Tailsitter *_tailsitter; // tiltrotor vtol type
|
||||
Standard *_standard; // standard vtol type
|
||||
|
||||
//*****************Member functions***********************************************************************
|
||||
|
||||
|
|
|
@ -31,12 +31,12 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file airframe.cpp
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file airframe.cpp
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#include "vtol_type.h"
|
||||
#include "drivers/drv_pwm_output.h"
|
||||
|
@ -44,8 +44,8 @@
|
|||
#include "vtol_att_control_main.h"
|
||||
|
||||
VtolType::VtolType(VtolAttitudeControl *att_controller) :
|
||||
_attc(att_controller),
|
||||
_vtol_mode(ROTARY_WING)
|
||||
_attc(att_controller),
|
||||
_vtol_mode(ROTARY_WING)
|
||||
{
|
||||
_v_att = _attc->get_att();
|
||||
_v_att_sp = _attc->get_att_sp();
|
||||
|
@ -70,7 +70,7 @@ _vtol_mode(ROTARY_WING)
|
|||
|
||||
VtolType::~VtolType()
|
||||
{
|
||||
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -31,12 +31,12 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file airframe.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file airframe.h
|
||||
*
|
||||
* @author Roman Bapst <bapstroman@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef VTOL_TYPE_H
|
||||
#define VTOL_TYPE_H
|
||||
|
@ -85,7 +85,7 @@ public:
|
|||
void set_idle_mc();
|
||||
void set_idle_fw();
|
||||
|
||||
mode get_mode () {return _vtol_mode;};
|
||||
mode get_mode() {return _vtol_mode;};
|
||||
|
||||
protected:
|
||||
VtolAttitudeControl *_attc;
|
||||
|
|
Loading…
Reference in New Issue