|
|
@ -66,10 +66,7 @@ void Rover::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; |
|
|
|
|
|
|
|
|
|
|
|
mavlink_msg_heartbeat_send( |
|
|
|
gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_GROUND_ROVER, |
|
|
|
chan, |
|
|
|
|
|
|
|
MAV_TYPE_GROUND_ROVER, |
|
|
|
|
|
|
|
MAV_AUTOPILOT_ARDUPILOTMEGA, |
|
|
|
|
|
|
|
base_mode, |
|
|
|
base_mode, |
|
|
|
custom_mode, |
|
|
|
custom_mode, |
|
|
|
system_status); |
|
|
|
system_status); |
|
|
|