Skip to content

Commit

Permalink
MAVLink app: Enable protocol version handshaking
Browse files Browse the repository at this point in the history
This allows the ground control station or any other communication partner to query the supported versions. The key aspect is to send the response in MAVLink 2 framing to test the link with a MAVLink 2 framed message.
  • Loading branch information
LorenzMeier committed Jun 4, 2017
1 parent 990ae93 commit 8c3b900
Show file tree
Hide file tree
Showing 3 changed files with 37 additions and 0 deletions.
21 changes: 21 additions & 0 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1302,6 +1302,27 @@ void Mavlink::send_autopilot_capabilites()
}
}

void Mavlink::send_protocol_version()
{
mavlink_protocol_version_t msg = {};

msg.version = _protocol_version * 100;
msg.min_version = 100;
msg.max_version = 200;
uint64_t mavlink_lib_git_version_binary = px4_mavlink_lib_version_binary();
// TODO add when available
//memcpy(&msg.spec_version_hash, &mavlink_spec_git_version_binary, sizeof(msg.spec_version_hash));
memcpy(&msg.library_version_hash, &mavlink_lib_git_version_binary, sizeof(msg.library_version_hash));

// Switch to MAVLink 2
int curr_proto_ver = _protocol_version;
set_proto_version(2);
// Send response - if it passes through the link its fine to use MAVLink 2
mavlink_msg_protocol_version_send_struct(get_channel(), &msg);
// Reset to previous value
set_proto_version(curr_proto_ver);
}

MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic, int instance)
{
/* check if already subscribed to this topic */
Expand Down
9 changes: 9 additions & 0 deletions src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -344,8 +344,17 @@ class Mavlink
* @param severity the log level
*/
void send_statustext(unsigned char severity, const char *string);

/**
* Send the capabilities of this autopilot in terms of the MAVLink spec
*/
void send_autopilot_capabilites();

/**
* Send the protocol version of MAVLink
*/
void send_protocol_version();

MavlinkStream *get_streams() const { return _streams; }

float get_rate_mult();
Expand Down
7 changes: 7 additions & 0 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -362,6 +362,9 @@ MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_c
switch (command) {

case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:

/* fallthrough */
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
/* broadcast and ignore component */
target_ok = (target_system == 0) || (target_system == mavlink_system.sysid);
break;
Expand Down Expand Up @@ -406,6 +409,10 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
/* send autopilot version message */
_mavlink->send_autopilot_capabilites();

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
/* send protocol version message */
_mavlink->send_protocol_version();

} else if (cmd_mavlink.command == MAV_CMD_GET_HOME_POSITION) {
_mavlink->configure_stream_threadsafe("HOME_POSITION", 0.5f);

Expand Down

0 comments on commit 8c3b900

Please sign in to comment.