Browse Source

update mavlink submodule to latest

- update MAV_TYPE VTOL usage for current mavlink
v1.13.0-BW
Daniel Agar 3 years ago committed by Lorenz Meier
parent
commit
98623f69a3
  1. 2
      ROMFS/px4fmu_common/init.d/rc.vtol_defaults
  2. 22
      src/modules/commander/commander_helper.cpp
  3. 2
      src/modules/mavlink/mavlink
  4. 7
      src/modules/mavlink/mavlink_params.c
  5. 8
      src/modules/mavlink/mavlink_receiver.cpp
  6. 12
      src/modules/mavlink/streams/HIL_ACTUATOR_CONTROLS.hpp
  7. 8
      src/modules/simulator/simulator_mavlink.cpp

2
ROMFS/px4fmu_common/init.d/rc.vtol_defaults

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
set VEHICLE_TYPE vtol
# MAV_TYPE_VTOL_RESERVED2 22
# MAV_TYPE_VTOL_FIXEDROTOR 22
param set-default MAV_TYPE 22
param set-default MIS_TAKEOFF_ALT 20

22
src/modules/commander/commander_helper.cpp

@ -74,10 +74,11 @@ @@ -74,10 +74,11 @@
#define VEHICLE_TYPE_HEXAROTOR 13
#define VEHICLE_TYPE_OCTOROTOR 14
#define VEHICLE_TYPE_TRICOPTER 15
#define VEHICLE_TYPE_VTOL_DUOROTOR 19
#define VEHICLE_TYPE_VTOL_QUADROTOR 20
#define VEHICLE_TYPE_VTOL_TAILSITTER_DUOROTOR 19
#define VEHICLE_TYPE_VTOL_TAILSITTER_QUADROTOR 20
#define VEHICLE_TYPE_VTOL_TILTROTOR 21
#define VEHICLE_TYPE_VTOL_RESERVED2 22 // VTOL standard
#define VEHICLE_TYPE_VTOL_FIXEDROTOR 22 // VTOL standard
#define VEHICLE_TYPE_VTOL_TAILSITTER 23
#define BLINK_MSG_TIME 700000 // 3 fast blinks (in us)
@ -91,22 +92,25 @@ bool is_multirotor(const vehicle_status_s &current_status) @@ -91,22 +92,25 @@ bool is_multirotor(const vehicle_status_s &current_status)
bool is_rotary_wing(const vehicle_status_s &current_status)
{
return is_multirotor(current_status) || (current_status.system_type == VEHICLE_TYPE_HELICOPTER)
return is_multirotor(current_status)
|| (current_status.system_type == VEHICLE_TYPE_HELICOPTER)
|| (current_status.system_type == VEHICLE_TYPE_COAXIAL);
}
bool is_vtol(const vehicle_status_s &current_status)
{
return (current_status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR ||
return (current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER_DUOROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER_QUADROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_TILTROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_RESERVED2);
current_status.system_type == VEHICLE_TYPE_VTOL_FIXEDROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER);
}
bool is_vtol_tailsitter(const vehicle_status_s &current_status)
{
return (current_status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
return (current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER_DUOROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER_QUADROTOR ||
current_status.system_type == VEHICLE_TYPE_VTOL_TAILSITTER);
}
bool is_fixed_wing(const vehicle_status_s &current_status)

2
src/modules/mavlink/mavlink

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit b568a60fca42599d9998434e606f6e38e0b5e298
Subproject commit 0133e5db7fd640dcf250f3ba7817d6f0f7bb7589

7
src/modules/mavlink/mavlink_params.c

@ -90,10 +90,11 @@ PARAM_DEFINE_INT32(MAV_SIK_RADIO_ID, 0); @@ -90,10 +90,11 @@ PARAM_DEFINE_INT32(MAV_SIK_RADIO_ID, 0);
* @value 13 Hexarotor
* @value 14 Octorotor
* @value 15 Tricopter
* @value 19 VTOL Tailsitter Duo
* @value 20 VTOL Tailsitter Quad
* @value 19 VTOL Two-rotor Tailsitter
* @value 20 VTOL Quad-rotor Tailsitter
* @value 21 VTOL Tiltrotor
* @value 22 VTOL Standard (quadplane)
* @value 22 VTOL Standard (separate fixed rotors for hover and cruise flight)
* @value 23 VTOL Tailsitter
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_TYPE, 0);

8
src/modules/mavlink/mavlink_receiver.cpp

@ -1513,11 +1513,11 @@ void MavlinkReceiver::fill_thrust(float *thrust_body_array, uint8_t vehicle_type @@ -1513,11 +1513,11 @@ void MavlinkReceiver::fill_thrust(float *thrust_body_array, uint8_t vehicle_type
thrust_body_array[0] = thrust;
break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
switch (vehicle_type) {

12
src/modules/mavlink/streams/HIL_ACTUATOR_CONTROLS.hpp

@ -93,9 +93,9 @@ private: @@ -93,9 +93,9 @@ private:
if (system_type == MAV_TYPE_QUADROTOR ||
system_type == MAV_TYPE_HEXAROTOR ||
system_type == MAV_TYPE_OCTOROTOR ||
system_type == MAV_TYPE_VTOL_DUOROTOR ||
system_type == MAV_TYPE_VTOL_QUADROTOR ||
system_type == MAV_TYPE_VTOL_RESERVED2) {
system_type == MAV_TYPE_VTOL_TAILSITTER_DUOROTOR ||
system_type == MAV_TYPE_VTOL_TAILSITTER_QUADROTOR ||
system_type == MAV_TYPE_VTOL_FIXEDROTOR) {
/* multirotors: set number of rotor outputs depending on type */
@ -110,15 +110,15 @@ private: @@ -110,15 +110,15 @@ private:
n = 6;
break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
n = 2;
break;
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
n = 4;
break;
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_FIXEDROTOR:
n = 8;
break;

8
src/modules/simulator/simulator_mavlink.cpp

@ -114,7 +114,7 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t * @@ -114,7 +114,7 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t *
switch (_system_type) {
case MAV_TYPE_AIRSHIP:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_COAXIAL:
pos_thrust_motors_count = 2;
is_fixed_wing = false;
@ -126,13 +126,13 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t * @@ -126,13 +126,13 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t *
break;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
pos_thrust_motors_count = 4;
is_fixed_wing = false;
break;
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_FIXEDROTOR:
pos_thrust_motors_count = 5;
is_fixed_wing = false;
break;
@ -142,7 +142,7 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t * @@ -142,7 +142,7 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t *
is_fixed_wing = false;
break;
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_TAILSITTER:
// this is the tricopter VTOL / quad plane with 3 motors and 2 servos
pos_thrust_motors_count = 3;
is_fixed_wing = false;

Loading…
Cancel
Save