Commit cb2892bc authored by Don Gagne's avatar Don Gagne

One heartbeat per-link, not per-vehicle

parent 128b8d8e
...@@ -303,20 +303,27 @@ void MultiVehicleManager::setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled) ...@@ -303,20 +303,27 @@ void MultiVehicleManager::setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled)
void MultiVehicleManager::_sendGCSHeartbeat(void) void MultiVehicleManager::_sendGCSHeartbeat(void)
{ {
for (int i=0; i< _vehicles.count(); i++) { // Send a heartbeat out on each link
Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]); QmlObjectListModel* links = _toolbox->linkManager()->links();
for (int i=0; i<links->count(); i++) {
mavlink_message_t message; LinkInterface* link = links->value<LinkInterface*>(i);
mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(), if (link->isConnected()) {
_mavlinkProtocol->getComponentId(), mavlink_message_t message;
vehicle->priorityLink()->mavlinkChannel(), mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
&message, _mavlinkProtocol->getComponentId(),
MAV_TYPE_GCS, // MAV_TYPE link->mavlinkChannel(),
MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT &message,
MAV_MODE_MANUAL_ARMED, // MAV_MODE MAV_TYPE_GCS, // MAV_TYPE
0, // custom mode MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT
MAV_STATE_ACTIVE); // MAV_STATE MAV_MODE_MANUAL_ARMED, // MAV_MODE
vehicle->sendMessageOnLink(vehicle->priorityLink(), message); 0, // custom mode
MAV_STATE_ACTIVE); // MAV_STATE
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message);
link->writeBytesSafe((const char*)buffer, len);
}
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment