Rover: send correct mav-type for boats

This commit is contained in:
Randy Mackay 2018-03-21 14:40:53 +09:00
parent 5662aa1b75
commit b5e0a2ea8b
2 changed files with 3 additions and 2 deletions

View File

@ -54,7 +54,8 @@ void Rover::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_GROUND_ROVER,
gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(
is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER,
base_mode,
control_mode->mode_number(),
system_status);

View File

@ -79,7 +79,7 @@ void Rover::init_ardupilot()
// setup frsky telemetry
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.init(serial_manager, fwver.fw_string, MAV_TYPE_GROUND_ROVER);
frsky_telemetry.init(serial_manager, fwver.fw_string, (is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER));
#endif
#if LOGGING_ENABLED == ENABLED