Browse Source

Set tailsitter flag via vehicle status

Removes the necessity of including vtol_type.h in other modules.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
main
Silvan Fuhrer 3 years ago
parent
commit
d8444df11c
  1. 23
      src/modules/fw_att_control/FixedwingAttitudeControl.cpp
  2. 2
      src/modules/fw_att_control/FixedwingAttitudeControl.hpp
  3. 9
      src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
  4. 2
      src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
  5. 1
      src/modules/mc_att_control/mc_att_control.hpp
  6. 9
      src/modules/mc_att_control/mc_att_control_main.cpp

23
src/modules/fw_att_control/FixedwingAttitudeControl.cpp

@ -33,8 +33,6 @@
#include "FixedwingAttitudeControl.hpp" #include "FixedwingAttitudeControl.hpp"
#include <vtol_att_control/vtol_type.h>
using namespace time_literals; using namespace time_literals;
using math::constrain; using math::constrain;
using math::gradual; using math::gradual;
@ -48,15 +46,6 @@ FixedwingAttitudeControl::FixedwingAttitudeControl(bool vtol) :
_attitude_sp_pub(vtol ? ORB_ID(fw_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)), _attitude_sp_pub(vtol ? ORB_ID(fw_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)),
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle"))
{ {
// check if VTOL first
if (vtol) {
int32_t vt_type = -1;
if (param_get(param_find("VT_TYPE"), &vt_type) == PX4_OK) {
_is_tailsitter = (static_cast<vtol_type>(vt_type) == vtol_type::TAILSITTER);
}
}
/* fetch initial parameter values */ /* fetch initial parameter values */
parameters_update(); parameters_update();
@ -128,7 +117,7 @@ FixedwingAttitudeControl::vehicle_control_mode_poll()
if (_vehicle_status.is_vtol) { if (_vehicle_status.is_vtol) {
const bool is_hovering = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING const bool is_hovering = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
&& !_vehicle_status.in_transition_mode; && !_vehicle_status.in_transition_mode;
const bool is_tailsitter_transition = _vehicle_status.in_transition_mode && _is_tailsitter; const bool is_tailsitter_transition = _vehicle_status.in_transition_mode && _vehicle_status.is_vtol_tailsitter;
if (is_hovering || is_tailsitter_transition) { if (is_hovering || is_tailsitter_transition) {
_vcontrol_mode.flag_control_attitude_enabled = false; _vcontrol_mode.flag_control_attitude_enabled = false;
@ -140,7 +129,7 @@ FixedwingAttitudeControl::vehicle_control_mode_poll()
void void
FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body) FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body)
{ {
const bool is_tailsitter_transition = _is_tailsitter && _vehicle_status.in_transition_mode; const bool is_tailsitter_transition = _vehicle_status.is_vtol_tailsitter && _vehicle_status.in_transition_mode;
const bool is_fixed_wing = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING; const bool is_fixed_wing = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
if (_vcontrol_mode.flag_control_manual_enabled && (!is_tailsitter_transition || is_fixed_wing)) { if (_vcontrol_mode.flag_control_manual_enabled && (!is_tailsitter_transition || is_fixed_wing)) {
@ -212,7 +201,7 @@ void
FixedwingAttitudeControl::vehicle_rates_setpoint_poll() FixedwingAttitudeControl::vehicle_rates_setpoint_poll()
{ {
if (_rates_sp_sub.update(&_rates_sp)) { if (_rates_sp_sub.update(&_rates_sp)) {
if (_is_tailsitter) { if (_vehicle_status.is_vtol_tailsitter) {
float tmp = _rates_sp.roll; float tmp = _rates_sp.roll;
_rates_sp.roll = -_rates_sp.yaw; _rates_sp.roll = -_rates_sp.yaw;
_rates_sp.yaw = tmp; _rates_sp.yaw = tmp;
@ -311,7 +300,7 @@ void FixedwingAttitudeControl::Run()
float pitchspeed = angular_velocity.xyz[1]; float pitchspeed = angular_velocity.xyz[1];
float yawspeed = angular_velocity.xyz[2]; float yawspeed = angular_velocity.xyz[2];
if (_is_tailsitter) { if (_vehicle_status.is_vtol_tailsitter) {
/* vehicle is a tailsitter, we need to modify the estimated attitude for fw mode /* vehicle is a tailsitter, we need to modify the estimated attitude for fw mode
* *
* Since the VTOL airframe is initialized as a multicopter we need to * Since the VTOL airframe is initialized as a multicopter we need to
@ -379,7 +368,7 @@ void FixedwingAttitudeControl::Run()
// lock integrator if no rate control enabled, or in RW mode (but not transitioning VTOL or tailsitter), or for long intervals (> 20 ms) // lock integrator if no rate control enabled, or in RW mode (but not transitioning VTOL or tailsitter), or for long intervals (> 20 ms)
bool lock_integrator = !_vcontrol_mode.flag_control_rates_enabled bool lock_integrator = !_vcontrol_mode.flag_control_rates_enabled
|| (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && || (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING &&
!_vehicle_status.in_transition_mode && !_is_tailsitter) !_vehicle_status.in_transition_mode && !_vehicle_status.is_vtol_tailsitter)
|| (dt > 0.02f); || (dt > 0.02f);
/* if we are in rotary wing mode, do nothing */ /* if we are in rotary wing mode, do nothing */
@ -417,7 +406,7 @@ void FixedwingAttitudeControl::Run()
*/ */
if (_landed if (_landed
|| (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING || (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
&& !_vehicle_status.in_transition_mode && !_is_tailsitter)) { && !_vehicle_status.in_transition_mode && !_vehicle_status.is_vtol_tailsitter)) {
_roll_ctrl.reset_integrator(); _roll_ctrl.reset_integrator();
_pitch_ctrl.reset_integrator(); _pitch_ctrl.reset_integrator();

2
src/modules/fw_att_control/FixedwingAttitudeControl.hpp

@ -151,8 +151,6 @@ private:
bool _flag_control_attitude_enabled_last{false}; bool _flag_control_attitude_enabled_last{false};
bool _is_tailsitter{false};
float _energy_integration_time{0.0f}; float _energy_integration_time{0.0f};
float _control_energy[4] {}; float _control_energy[4] {};
float _control_prev[3] {}; float _control_prev[3] {};

9
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp

@ -33,7 +33,6 @@
#include "FixedwingPositionControl.hpp" #include "FixedwingPositionControl.hpp"
#include <vtol_att_control/vtol_type.h>
#include <px4_platform_common/events.h> #include <px4_platform_common/events.h>
using math::constrain; using math::constrain;
@ -59,12 +58,6 @@ FixedwingPositionControl::FixedwingPositionControl(bool vtol) :
{ {
if (vtol) { if (vtol) {
_param_handle_airspeed_trans = param_find("VT_ARSP_TRANS"); _param_handle_airspeed_trans = param_find("VT_ARSP_TRANS");
// VTOL parameter VTOL_TYPE
int32_t vt_type = -1;
param_get(param_find("VT_TYPE"), &vt_type);
_vtol_tailsitter = (static_cast<vtol_type>(vt_type) == vtol_type::TAILSITTER);
} }
// limit to 50 Hz // limit to 50 Hz
@ -370,7 +363,7 @@ FixedwingPositionControl::vehicle_attitude_poll()
// if the vehicle is a tailsitter we have to rotate the attitude by the pitch offset // if the vehicle is a tailsitter we have to rotate the attitude by the pitch offset
// between multirotor and fixed wing flight // between multirotor and fixed wing flight
if (_vtol_tailsitter) { if (_vehicle_status.is_vtol_tailsitter) {
const Dcmf R_offset{Eulerf{0.f, M_PI_2_F, 0.f}}; const Dcmf R_offset{Eulerf{0.f, M_PI_2_F, 0.f}};
R = R * R_offset; R = R * R_offset;

2
src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp

@ -95,7 +95,6 @@
#include <uORB/topics/wind.h> #include <uORB/topics/wind.h>
#include <uORB/topics/orbit_status.h> #include <uORB/topics/orbit_status.h>
#include <uORB/uORB.h> #include <uORB/uORB.h>
#include <vtol_att_control/vtol_type.h>
using namespace launchdetection; using namespace launchdetection;
using namespace runwaytakeoff; using namespace runwaytakeoff;
@ -527,7 +526,6 @@ private:
(ParamFloat<px4::params::FW_TKO_PITCH_MIN>) _takeoff_pitch_min, (ParamFloat<px4::params::FW_TKO_PITCH_MIN>) _takeoff_pitch_min,
(ParamFloat<px4::params::NAV_FW_ALT_RAD>) _param_nav_fw_alt_rad (ParamFloat<px4::params::NAV_FW_ALT_RAD>) _param_nav_fw_alt_rad
) )
}; };

1
src/modules/mc_att_control/mc_att_control.hpp

@ -54,7 +54,6 @@
#include <uORB/topics/vehicle_rates_setpoint.h> #include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_status.h> #include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_land_detected.h> #include <uORB/topics/vehicle_land_detected.h>
#include <vtol_att_control/vtol_type.h>
#include <lib/mathlib/math/filter/AlphaFilter.hpp> #include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <AttitudeControl.hpp> #include <AttitudeControl.hpp>

9
src/modules/mc_att_control/mc_att_control_main.cpp

@ -58,13 +58,6 @@ MulticopterAttitudeControl::MulticopterAttitudeControl(bool vtol) :
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")), _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")),
_vtol(vtol) _vtol(vtol)
{ {
if (_vtol) {
int32_t vt_type = -1;
if (param_get(param_find("VT_TYPE"), &vt_type) == PX4_OK) {
_vtol_tailsitter = (static_cast<vtol_type>(vt_type) == vtol_type::TAILSITTER);
}
}
parameters_updated(); parameters_updated();
} }
@ -301,6 +294,8 @@ MulticopterAttitudeControl::Run()
_vehicle_type_rotary_wing = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING); _vehicle_type_rotary_wing = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING);
_vtol = vehicle_status.is_vtol; _vtol = vehicle_status.is_vtol;
_vtol_in_transition_mode = vehicle_status.in_transition_mode; _vtol_in_transition_mode = vehicle_status.in_transition_mode;
_vtol_tailsitter = vehicle_status.is_vtol_tailsitter;
} }
} }

Loading…
Cancel
Save