diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 4acaac90a6..40bee8e291 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1427,8 +1427,21 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * mission_item->params[1] = mavlink_mission_item->param2; mission_item->params[2] = mavlink_mission_item->param3; mission_item->params[3] = mavlink_mission_item->param4; - mission_item->params[4] = mavlink_mission_item->x; - mission_item->params[5] = mavlink_mission_item->y; + + if (_int_mode) { + /* The argument is actually a mavlink_mission_item_int_t in int_mode. + * mavlink_mission_item_t and mavlink_mission_item_int_t have the same + * alignment, so we can just swap float for int32_t. */ + const mavlink_mission_item_int_t *item_int + = reinterpret_cast(mavlink_mission_item); + mission_item->params[4] = ((double)item_int->x); + mission_item->params[5] = ((double)item_int->y); + + } else { + mission_item->params[4] = (double)mavlink_mission_item->x; + mission_item->params[5] = (double)mavlink_mission_item->y; + } + mission_item->params[6] = mavlink_mission_item->z; switch (mavlink_mission_item->command) { @@ -1519,8 +1532,25 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * mavlink_mission_item->param2 = mission_item->params[1]; mavlink_mission_item->param3 = mission_item->params[2]; mavlink_mission_item->param4 = mission_item->params[3]; + mavlink_mission_item->x = mission_item->params[4]; mavlink_mission_item->y = mission_item->params[5]; + + if (_int_mode) { + // This function actually receives a mavlink_mission_item_int_t in _int_mode + // which has the same alignment as mavlink_mission_item_t and the only + // difference is int32_t vs. float for x and y. + mavlink_mission_item_int_t *item_int = + reinterpret_cast(mavlink_mission_item); + + item_int->x = round(mission_item->params[4]); + item_int->y = round(mission_item->params[5]); + + } else { + mavlink_mission_item->x = (float)mission_item->params[4]; + mavlink_mission_item->y = (float)mission_item->params[5]; + } + mavlink_mission_item->z = mission_item->params[6]; switch (mavlink_mission_item->command) {