Commit f5e60b5e authored by Don Gagne's avatar Don Gagne

Fix encode_chan usage

Must memset structures before use.
parent 173f35ac
...@@ -602,15 +602,12 @@ void APMSensorsComponentController::cancelCalibration(void) ...@@ -602,15 +602,12 @@ void APMSensorsComponentController::cancelCalibration(void)
void APMSensorsComponentController::nextClicked(void) void APMSensorsComponentController::nextClicked(void)
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_command_ack_t ack; mavlink_msg_command_ack_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
ack.command = 0;
ack.result = 1;
mavlink_msg_command_ack_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(), _vehicle->priorityLink()->mavlinkChannel(),
&msg, &msg,
&ack); 0, // command
1); // result
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
......
...@@ -666,6 +666,8 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN ...@@ -666,6 +666,8 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN
mavlink_param_set_t p; mavlink_param_set_t p;
mavlink_param_union_t union_value; mavlink_param_union_t union_value;
memset(&p, 0, sizeof(p));
FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type(); FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type();
p.param_type = _factTypeToMavType(factType); p.param_type = _factTypeToMavType(factType);
...@@ -786,6 +788,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ...@@ -786,6 +788,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
// Return the hash value to notify we don't want any more updates // Return the hash value to notify we don't want any more updates
mavlink_param_set_t p; mavlink_param_set_t p;
mavlink_param_union_t union_value; mavlink_param_union_t union_value;
memset(&p, 0, sizeof(p));
p.param_type = MAV_PARAM_TYPE_UINT32; p.param_type = MAV_PARAM_TYPE_UINT32;
strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id)); strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id));
union_value.param_uint32 = crc32_value; union_value.param_uint32 = crc32_value;
......
...@@ -228,6 +228,8 @@ void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_mess ...@@ -228,6 +228,8 @@ void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_mess
mavlink_param_value_t paramValue; mavlink_param_value_t paramValue;
mavlink_param_union_t paramUnion; mavlink_param_union_t paramUnion;
memset(&paramValue, 0, sizeof(paramValue));
// APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
// type they are. Fix that up to correct usage. // type they are. Fix that up to correct usage.
...@@ -278,6 +280,8 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* ...@@ -278,6 +280,8 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface*
mavlink_param_set_t paramSet; mavlink_param_set_t paramSet;
mavlink_param_union_t paramUnion; mavlink_param_union_t paramUnion;
memset(&paramSet, 0, sizeof(paramSet));
// APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
// type they are. Fix it back to the wrong way on the way out. // type they are. Fix it back to the wrong way on the way out.
......
...@@ -184,7 +184,7 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double ...@@ -184,7 +184,7 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
mavlink_message_t msg; mavlink_message_t msg;
mavlink_set_position_target_local_ned_t cmd; mavlink_set_position_target_local_ned_t cmd;
memset(&cmd, 0, sizeof(mavlink_set_position_target_local_ned_t)); memset(&cmd, 0, sizeof(cmd));
cmd.target_system = vehicle->id(); cmd.target_system = vehicle->id();
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
......
...@@ -119,7 +119,7 @@ void FollowMe::_sendGCSMotionReport(void) ...@@ -119,7 +119,7 @@ void FollowMe::_sendGCSMotionReport(void)
MAVLinkProtocol* mavlinkProtocol = _toolbox->mavlinkProtocol(); MAVLinkProtocol* mavlinkProtocol = _toolbox->mavlinkProtocol();
mavlink_follow_target_t follow_target; mavlink_follow_target_t follow_target;
memset(&follow_target, 0, sizeof(mavlink_follow_target_t)); memset(&follow_target, 0, sizeof(follow_target));
follow_target.timestamp = runTime.nsecsElapsed()*1e-6; follow_target.timestamp = runTime.nsecsElapsed()*1e-6;
follow_target.est_capabilities = estimatation_capabilities; follow_target.est_capabilities = estimatation_capabilities;
......
...@@ -110,6 +110,7 @@ void MissionManager::_writeMissionCount(void) ...@@ -110,6 +110,7 @@ void MissionManager::_writeMissionCount(void)
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_count_t missionCount; mavlink_mission_count_t missionCount;
memset(&missionCount, 0, sizeof(missionCount));
missionCount.target_system = _vehicle->id(); missionCount.target_system = _vehicle->id();
missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionCount.count = _missionItems.count(); missionCount.count = _missionItems.count();
...@@ -137,6 +138,7 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC ...@@ -137,6 +138,7 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
mavlink_message_t messageOut; mavlink_message_t messageOut;
mavlink_mission_item_t missionItem; mavlink_mission_item_t missionItem;
memset(&missionItem, 8, sizeof(missionItem));
missionItem.target_system = _vehicle->id(); missionItem.target_system = _vehicle->id();
missionItem.target_component = _vehicle->defaultComponentId(); missionItem.target_component = _vehicle->defaultComponentId();
missionItem.seq = 0; missionItem.seq = 0;
...@@ -191,6 +193,8 @@ void MissionManager::_requestList(void) ...@@ -191,6 +193,8 @@ void MissionManager::_requestList(void)
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_request_list_t request; mavlink_mission_request_list_t request;
memset(&request, 0, sizeof(request));
_itemIndicesToRead.clear(); _itemIndicesToRead.clear();
_clearMissionItems(); _clearMissionItems();
...@@ -307,6 +311,8 @@ void MissionManager::_readTransactionComplete(void) ...@@ -307,6 +311,8 @@ void MissionManager::_readTransactionComplete(void)
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_ack_t missionAck; mavlink_mission_ack_t missionAck;
memset(&missionAck, 0, sizeof(missionAck));
missionAck.target_system = _vehicle->id(); missionAck.target_system = _vehicle->id();
missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER; missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionAck.type = MAV_MISSION_ACCEPTED; missionAck.type = MAV_MISSION_ACCEPTED;
...@@ -360,6 +366,7 @@ void MissionManager::_requestNextMissionItem(void) ...@@ -360,6 +366,7 @@ void MissionManager::_requestNextMissionItem(void)
if (_vehicle->supportsMissionItemInt()) { if (_vehicle->supportsMissionItemInt()) {
mavlink_mission_request_int_t missionRequest; mavlink_mission_request_int_t missionRequest;
memset(&missionRequest, 0, sizeof(missionRequest));
missionRequest.target_system = _vehicle->id(); missionRequest.target_system = _vehicle->id();
missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER; missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionRequest.seq = _itemIndicesToRead[0]; missionRequest.seq = _itemIndicesToRead[0];
...@@ -372,6 +379,7 @@ void MissionManager::_requestNextMissionItem(void) ...@@ -372,6 +379,7 @@ void MissionManager::_requestNextMissionItem(void)
} else { } else {
mavlink_mission_request_t missionRequest; mavlink_mission_request_t missionRequest;
memset(&missionRequest, 0, sizeof(missionRequest));
missionRequest.target_system = _vehicle->id(); missionRequest.target_system = _vehicle->id();
missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER; missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionRequest.seq = _itemIndicesToRead[0]; missionRequest.seq = _itemIndicesToRead[0];
...@@ -523,7 +531,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo ...@@ -523,7 +531,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
if (missionItemInt) { if (missionItemInt) {
mavlink_mission_item_int_t missionItem; mavlink_mission_item_int_t missionItem;
memset(&missionItem, 0, sizeof(missionItem));
missionItem.target_system = _vehicle->id(); missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER; missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionItem.seq = missionRequest.seq; missionItem.seq = missionRequest.seq;
...@@ -547,6 +555,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo ...@@ -547,6 +555,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
} else { } else {
mavlink_mission_item_t missionItem; mavlink_mission_item_t missionItem;
memset(&missionItem, 0, sizeof(missionItem));
missionItem.target_system = _vehicle->id(); missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER; missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionItem.seq = missionRequest.seq; missionItem.seq = missionRequest.seq;
......
...@@ -1523,6 +1523,8 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send ...@@ -1523,6 +1523,8 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t dataStream; mavlink_request_data_stream_t dataStream;
memset(&dataStream, 0, sizeof(dataStream));
dataStream.req_stream_id = stream; dataStream.req_stream_id = stream;
dataStream.req_message_rate = rate; dataStream.req_message_rate = rate;
dataStream.start_stop = 1; // start dataStream.start_stop = 1; // start
...@@ -2079,6 +2081,7 @@ void Vehicle::_sendMavCommandAgain(void) ...@@ -2079,6 +2081,7 @@ void Vehicle::_sendMavCommandAgain(void)
mavlink_message_t msg; mavlink_message_t msg;
mavlink_command_long_t cmd; mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.command = queuedCommand.command; cmd.command = queuedCommand.command;
cmd.confirmation = 0; cmd.confirmation = 0;
cmd.param1 = queuedCommand.rgParam[0]; cmd.param1 = queuedCommand.rgParam[0];
...@@ -2304,6 +2307,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence) ...@@ -2304,6 +2307,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence)
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_logging_ack_t ack; mavlink_logging_ack_t ack;
memset(&ack, 0, sizeof(ack));
ack.sequence = sequence; ack.sequence = sequence;
ack.target_component = _defaultComponentId; ack.target_component = _defaultComponentId;
ack.target_system = id(); ack.target_system = id();
......
...@@ -240,6 +240,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber) ...@@ -240,6 +240,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_request_t missionRequest; mavlink_mission_request_t missionRequest;
memset(&missionRequest, 0, sizeof(missionRequest));
missionRequest.target_system = _mavlinkProtocol->getSystemId(); missionRequest.target_system = _mavlinkProtocol->getSystemId();
missionRequest.target_component = _mavlinkProtocol->getComponentId(); missionRequest.target_component = _mavlinkProtocol->getComponentId();
missionRequest.seq = sequenceNumber; missionRequest.seq = sequenceNumber;
...@@ -264,6 +265,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) ...@@ -264,6 +265,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_ack_t missionAck; mavlink_mission_ack_t missionAck;
memset(&missionAck, 0, sizeof(missionAck));
missionAck.target_system = _mavlinkProtocol->getSystemId(); missionAck.target_system = _mavlinkProtocol->getSystemId();
missionAck.target_component = _mavlinkProtocol->getComponentId(); missionAck.target_component = _mavlinkProtocol->getComponentId();
missionAck.type = ackType; missionAck.type = ackType;
......
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