mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: make mav_type in HEARTBEAT configurable
needed for qgc to setup for quadplanes
This commit is contained in:
parent
0aed5a9a57
commit
8178ab4037
@ -90,7 +90,7 @@ void Plane::send_heartbeat(mavlink_channel_t chan)
|
|||||||
// indicate we have set a custom mode
|
// indicate we have set a custom mode
|
||||||
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||||
|
|
||||||
gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(MAV_TYPE_FIXED_WING,
|
gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(quadplane.get_mav_type(),
|
||||||
base_mode,
|
base_mode,
|
||||||
custom_mode,
|
custom_mode,
|
||||||
system_status);
|
system_status);
|
||||||
|
@ -394,6 +394,12 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("TAILSIT_VHPOW", 56, QuadPlane, tailsitter.vectored_hover_power, 2.5),
|
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
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -2401,3 +2407,14 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
|
|||||||
guided_takeoff = true;
|
guided_takeoff = true;
|
||||||
return 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());
|
||||||
|
}
|
||||||
|
@ -249,6 +249,10 @@ private:
|
|||||||
// ICEngine control on landing
|
// ICEngine control on landing
|
||||||
AP_Int8 land_icengine_cut;
|
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
|
// time we last got an EKF yaw reset
|
||||||
uint32_t ekfYawReset_ms;
|
uint32_t ekfYawReset_ms;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user