From 8178ab4037b05c515946f1f3fe501babaf48ad5b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 20 Oct 2017 15:39:44 +1100 Subject: [PATCH] Plane: make mav_type in HEARTBEAT configurable needed for qgc to setup for quadplanes --- ArduPlane/GCS_Mavlink.cpp | 8 ++++---- ArduPlane/quadplane.cpp | 17 +++++++++++++++++ ArduPlane/quadplane.h | 4 ++++ 3 files changed, 25 insertions(+), 4 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index fdf6dc6786..56fac55b13 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -90,10 +90,10 @@ void Plane::send_heartbeat(mavlink_channel_t chan) // indicate we have set a custom mode base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; - gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(MAV_TYPE_FIXED_WING, - base_mode, - custom_mode, - system_status); + gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(quadplane.get_mav_type(), + base_mode, + custom_mode, + system_status); } void Plane::send_attitude(mavlink_channel_t chan) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 42863d7668..d9199f4b4e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -393,6 +393,12 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Range: 0 4 // @Increment: 0.1 AP_GROUPINFO("TAILSIT_VHPOW", 56, QuadPlane, tailsitter.vectored_hover_power, 2.5), + + // @Param: MAV_TYPE + // @DisplayName: MAVLink type identifier + // @Description: This controls the mavlink type given in HEARTBEAT messages. For some GCS types a particular setting will be needed for correct operation. + // @Values: 0:AUTO,1:FIXED_WING,2:QUADROTOR,3:COAXIAL,4:HELICOPTER,7:AIRSHIP,8:FREE_BALLOON,9:ROCKET,10:GROUND_ROVER,11:SURFACE_BOAT,12:SUBMARINE,16:FLAPPING_WING,17:KITE,19:VTOL_DUOROTOR,20:VTOL_QUADROTOR,21:VTOL_TILTROTOR + AP_GROUPINFO("MAV_TYPE", 57, QuadPlane, mav_type, 0), AP_GROUPEND }; @@ -2401,3 +2407,14 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude) guided_takeoff = true; return true; } + +/* + return mav_type for heartbeat + */ +uint8_t QuadPlane::get_mav_type(void) const +{ + if (mav_type.get() == 0) { + return MAV_TYPE_FIXED_WING; + } + return uint8_t(mav_type.get()); +} diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 363348d79a..d945461cfb 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -249,6 +249,10 @@ private: // ICEngine control on landing AP_Int8 land_icengine_cut; + // HEARTBEAT mav_type override + AP_Int8 mav_type; + uint8_t get_mav_type(void) const; + // time we last got an EKF yaw reset uint32_t ekfYawReset_ms;