Rover: use send_heartbeat() wrapper
This commit is contained in:
parent
273c80116a
commit
01caa7388a
@ -66,13 +66,10 @@ void Rover::send_heartbeat(mavlink_channel_t chan)
|
||||
// indicate we have set a custom mode
|
||||
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
|
||||
mavlink_msg_heartbeat_send(
|
||||
chan,
|
||||
MAV_TYPE_GROUND_ROVER,
|
||||
MAV_AUTOPILOT_ARDUPILOTMEGA,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_GROUND_ROVER,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
}
|
||||
|
||||
void Rover::send_attitude(mavlink_channel_t chan)
|
||||
|
Loading…
Reference in New Issue
Block a user