Unverified Commit 08d3ce1c authored by Don Gagne's avatar Don Gagne Committed by GitHub

Fix MISSION_ITEM_INT bugs (#9150)

parent b16a3a1f
...@@ -394,8 +394,8 @@ void PlanManager::_handleMissionItem(const mavlink_message_t& message, bool miss ...@@ -394,8 +394,8 @@ void PlanManager::_handleMissionItem(const mavlink_message_t& message, bool miss
param2 = missionItem.param2; param2 = missionItem.param2;
param3 = missionItem.param3; param3 = missionItem.param3;
param4 = missionItem.param4; param4 = missionItem.param4;
param5 = (double)missionItem.x / qPow(10.0, 7.0); param5 = missionItem.frame == MAV_FRAME_MISSION ? (double)missionItem.x : (double)missionItem.x * 1e-7;
param6 = (double)missionItem.y / qPow(10.0, 7.0); param6 = missionItem.frame == MAV_FRAME_MISSION ? (double)missionItem.y : (double)missionItem.x * 1e-7;
param7 = (double)missionItem.z; param7 = (double)missionItem.z;
autoContinue = missionItem.autocontinue; autoContinue = missionItem.autocontinue;
isCurrentItem = missionItem.current; isCurrentItem = missionItem.current;
...@@ -556,8 +556,8 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m ...@@ -556,8 +556,8 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
item->param2(), item->param2(),
item->param3(), item->param3(),
item->param4(), item->param4(),
item->param5() * qPow(10.0, 7.0), item->frame() == MAV_FRAME_MISSION ? item->param5() : item->param5() * 1e7,
item->param6() * qPow(10.0, 7.0), item->frame() == MAV_FRAME_MISSION ? item->param6() : item->param6() * 1e7,
item->param7(), item->param7(),
_planType); _planType);
} else { } else {
......
...@@ -2692,8 +2692,8 @@ void Vehicle::_sendMavCommandFromList(MavCommandListEntry_t& commandEntry) ...@@ -2692,8 +2692,8 @@ void Vehicle::_sendMavCommandFromList(MavCommandListEntry_t& commandEntry)
cmd.param2 = commandEntry.rgParam[1]; cmd.param2 = commandEntry.rgParam[1];
cmd.param3 = commandEntry.rgParam[2]; cmd.param3 = commandEntry.rgParam[2];
cmd.param4 = commandEntry.rgParam[3]; cmd.param4 = commandEntry.rgParam[3];
cmd.x = commandEntry.rgParam[4] * qPow(10.0, 7.0); cmd.x = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam[4] : commandEntry.rgParam[4] * 1e7;
cmd.y = commandEntry.rgParam[5] * qPow(10.0, 7.0); cmd.y = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam[5] : commandEntry.rgParam[5] * 1e7;
cmd.z = commandEntry.rgParam[6]; cmd.z = commandEntry.rgParam[6];
mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(), mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(), _mavlink->getComponentId(),
......
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