Commit 64eca014 authored by Don Gagne's avatar Don Gagne

Fix APM adjustMavlinkMessage

Previous code was horribly wrong.
parent 09f33f6b
...@@ -117,7 +117,7 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) ...@@ -117,7 +117,7 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
paramUnion.param_int32 = (int32_t)paramValue.param_value; paramUnion.param_int32 = (int32_t)paramValue.param_value;
break; break;
case MAV_PARAM_TYPE_REAL32: case MAV_PARAM_TYPE_REAL32:
// Already in param_float paramUnion.param_float = paramValue.param_value;
break; break;
default: default:
qCritical() << "Invalid/Unsupported data type used in parameter:" << paramValue.param_type; qCritical() << "Invalid/Unsupported data type used in parameter:" << paramValue.param_type;
...@@ -125,6 +125,8 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) ...@@ -125,6 +125,8 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
paramValue.param_value = paramUnion.param_float; paramValue.param_value = paramUnion.param_float;
mavlink_msg_param_value_encode(message->sysid, message->compid, message, &paramValue);
} else if (message->msgid == MAVLINK_MSG_ID_PARAM_SET) { } else if (message->msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t paramSet; mavlink_param_set_t paramSet;
mavlink_param_union_t paramUnion; mavlink_param_union_t paramUnion;
...@@ -161,6 +163,8 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) ...@@ -161,6 +163,8 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
default: default:
qCritical() << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type; qCritical() << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type;
} }
mavlink_msg_param_set_encode(message->sysid, message->compid, message, &paramSet);
} }
// FIXME: Need to implement mavlink message severity adjustment // FIXME: Need to implement mavlink message severity adjustment
......
...@@ -260,20 +260,16 @@ void Vehicle::_sendMessage(mavlink_message_t message) ...@@ -260,20 +260,16 @@ void Vehicle::_sendMessage(mavlink_message_t message)
if (link->isConnected()) { if (link->isConnected()) {
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
// Give the plugin a chance to adjust
_firmwarePlugin->adjustMavlinkMessage(&message);
// Write message into buffer, prepending start sign // Write message into buffer, prepending start sign
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message); int len = mavlink_msg_to_send_buffer(buffer, &message);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]); mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
// Give the plugin a chance to adjust
_firmwarePlugin->adjustMavlinkMessage(&message);
if (link->isConnected()) {
link->writeBytes((const char*)buffer, len); link->writeBytes((const char*)buffer, len);
} else {
qWarning() << "Link not connected";
}
} }
} }
} }
......
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