Skip to content

Commit

Permalink
Correct Autopilot type of Self (GCS)
Browse files Browse the repository at this point in the history
Currently GCS type (in Heartbeat) is MAV_AUTOPILOT_GENERIC (its a type for autopilot!).
However, MAVLink documentation recommends to use MAV_AUTOPILOT_INVALID for GCS.
  • Loading branch information
Shakthi Prashanth M committed Mar 6, 2018
1 parent f81d183 commit 688c85f
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion core/device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,8 +285,9 @@ void Device::device_thread(Device *self)
void Device::send_heartbeat(Device *self)
{
mavlink_message_t message;
// Self is GCS (its not autopilot!); hence MAV_AUTOPILOT_INVALID.
mavlink_msg_heartbeat_pack(_own_system_id, _own_component_id, &message,
MAV_TYPE_GCS, MAV_AUTOPILOT_GENERIC, 0, 0, 0);
MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, 0, 0, 0);
self->send_message(message);
}

Expand Down

0 comments on commit 688c85f

Please sign in to comment.