Skip to content

Commit

Permalink
Merge pull request #423 from dronecore/fix-json-null
Browse files Browse the repository at this point in the history
mission: import null as NaN
  • Loading branch information
julianoes authored Jun 13, 2018
2 parents 3e71a3c + 20676e4 commit aa86369
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 7 deletions.
7 changes: 6 additions & 1 deletion plugins/mission/mission_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1208,7 +1208,12 @@ Mission::Result MissionImpl::import_mission_items(Mission::mission_items_t &all_
// Extract parameters of each mission item
std::vector<double> params;
for (auto &p : json_mission_item["params"].array_items()) {
params.push_back(p.number_value());
if (p.is_null()) {
// QGC sets params as `null` if they should be unchanged.
params.push_back(NAN);
} else {
params.push_back(p.number_value());
}
}

result = build_mission_items(command, params, new_mission_item, all_mission_items);
Expand Down
12 changes: 6 additions & 6 deletions plugins/mission/mission_import_qgc_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ TEST(QGCMissionImport, ValidateQGCMissonItems)
// These mission items are meant to match those in
// file:://plugins/mission/qgroundcontrol_sample.plan
QGCMissionItem items_test[] = {
{MAV_CMD_NAV_TAKEOFF, {0., 0., 0., 0., 47.39781011, 8.54553801, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39779921, 8.54546693, 15.}},
{MAV_CMD_NAV_TAKEOFF, {0., 0., 0., double(NAN), 47.39781011, 8.54553801, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., double(NAN), 47.39779921, 8.54546693, 15.}},
{MAV_CMD_DO_MOUNT_CONTROL, {25.0, 0., 50.0}}, // Gimbal pitch & yaw in deg
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39773658, 8.54543743, 15.}},
{MAV_CMD_IMAGE_START_CAPTURE,
Expand All @@ -55,13 +55,13 @@ TEST(QGCMissionImport, ValidateQGCMissonItems)
1.,
0.,
}}, // Start image capture
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39768029, 8.54561177, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., double(NAN), 47.39768029, 8.54561177, 15.}},
{MAV_CMD_DO_CHANGE_SPEED, {1., 100., -1., 0}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39779649, 8.54566005, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., double(NAN), 47.39779649, 8.54566005, 15.}},
{MAV_CMD_NAV_LOITER_TIME, {30.}}, // Loiter for 30 seconds
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39779468, 8.54561445, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., double(NAN), 47.39779468, 8.54561445, 15.}},
{MAV_CMD_VIDEO_START_CAPTURE, {}}, // Start video capture
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., 0., 47.39784279, 8.54553533, 15.}},
{MAV_CMD_NAV_WAYPOINT, {0., 0., 0., double(NAN), 47.39784279, 8.54553533, 15.}},
{MAV_CMD_IMAGE_STOP_CAPTURE, {}}, // Stop image capture
{MAV_CMD_VIDEO_STOP_CAPTURE, {}}, // Stop video capture
};
Expand Down

0 comments on commit aa86369

Please sign in to comment.