GCS_MAVLink: added a wrapper for sending HEARTBEAT

will be used to cope with old radios with MAVLink2
This commit is contained in:
Andrew Tridgell 2016-05-17 08:36:49 +10:00
parent 2094cb2d88
commit 273c80116a
2 changed files with 15 additions and 0 deletions

View File

@ -163,6 +163,7 @@ public:
void send_vibration(const AP_InertialSensor &ins) const;
void send_home(const Location &home) const;
static void send_home_all(const Location &home);
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels

View File

@ -1580,3 +1580,17 @@ void GCS_MAVLINK::send_home_all(const Location &home)
}
}
}
/*
wrapper for sending heartbeat
*/
void GCS_MAVLINK::send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
mavlink_msg_heartbeat_send(
chan,
type,
MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode,
custom_mode,
system_status);
}