Skip to content

mission_raw: fix mission import for mission commands #2560

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
May 6, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 17 additions & 12 deletions src/mavsdk/plugins/mission_raw/mission_import.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,8 @@ MissionImport::import_mission(const Json::Value& root, Autopilot autopilot)
0.0f,
0.0f,
0.0f,
static_cast<int32_t>(std::round(home[0].asDouble() * 1e7)),
static_cast<int32_t>(std::round(home[1].asDouble() * 1e7)),
set_int32(home[0], MAV_FRAME_GLOBAL_INT),
set_int32(home[1], MAV_FRAME_GLOBAL_INT),
home[2].asFloat(),
MAV_MISSION_TYPE_MISSION});
}
Expand Down Expand Up @@ -225,8 +225,8 @@ MissionImport::import_rally_points(const Json::Value& root)
item.command = MAV_CMD_NAV_RALLY_POINT;
item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
item.mission_type = MAV_MISSION_TYPE_RALLY;
item.x = set_int32(point[0]);
item.y = set_int32(point[1]);
item.x = set_int32(point[0], item.frame);
item.y = set_int32(point[1], item.frame);
item.z = set_float(point[2]);

rally_items.push_back(item);
Expand Down Expand Up @@ -281,10 +281,10 @@ MissionImport::import_simple_mission_item(const Json::Value& json_item)
item.param4 = set_float(json_item["params"][i]);
break;
case 4:
item.x = set_int32(json_item["params"][i]);
item.x = set_int32(json_item["params"][i], item.frame);
break;
case 5:
item.y = set_int32(json_item["params"][i]);
item.y = set_int32(json_item["params"][i], item.frame);
break;
case 6:
item.z = set_float(json_item["params"][i]);
Expand Down Expand Up @@ -363,8 +363,8 @@ MissionImport::import_polygon_geofences(const Json::Value& polygons)
MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION;
item.frame = MAV_FRAME_GLOBAL;
item.param1 = set_float(points.size());
item.x = set_int32(point[0]);
item.y = set_int32(point[1]);
item.x = set_int32(point[0], item.frame);
item.y = set_int32(point[1], item.frame);
item.mission_type = MAV_MISSION_TYPE_FENCE;

polygon_geofences.push_back(item);
Expand All @@ -390,8 +390,8 @@ MissionImport::import_circular_geofences(const Json::Value& circles)
inclusion ? MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION : MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION;
item.frame = MAV_FRAME_GLOBAL;
item.param1 = set_float(radius);
item.x = set_int32(center[0]);
item.y = set_int32(center[1]);
item.x = set_int32(center[0], item.frame);
item.y = set_int32(center[1], item.frame);
item.mission_type = MAV_MISSION_TYPE_FENCE;

circular_geofences.push_back(item);
Expand All @@ -405,9 +405,14 @@ float MissionImport::set_float(const Json::Value& val)
return val.isNull() ? NAN : val.asFloat();
}

int32_t MissionImport::set_int32(const Json::Value& val)
int32_t MissionImport::set_int32(const Json::Value& val, uint32_t frame)
{
return static_cast<int32_t>(val.isNull() ? 0 : (std::round(val.asDouble() * 1e7)));
// Don't apply 10^7 conversion for MAV_FRAME_MISSION
if (frame == MAV_FRAME_MISSION) {
return static_cast<int32_t>(val.isNull() ? 0 : val.asFloat());
} else {
return static_cast<int32_t>(val.isNull() ? 0 : (std::round(val.asDouble() * 1e7)));
}
}

} // namespace mavsdk
2 changes: 1 addition & 1 deletion src/mavsdk/plugins/mission_raw/mission_import.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class MissionImport {
static std::vector<MissionRaw::MissionItem>
import_circular_geofences(const Json::Value& json_item);
static float set_float(const Json::Value& val);
static int32_t set_int32(const Json::Value& val);
static int32_t set_int32(const Json::Value& val, uint32_t frame);
};

} // namespace mavsdk
30 changes: 30 additions & 0 deletions src/mavsdk/plugins/mission_raw/mission_import_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -441,3 +441,33 @@ TEST(MissionRaw, ImportSamplePlanWithArduPilot)

EXPECT_EQ(reference_items, result_pair.second.mission_items);
}

TEST(MissionRaw, ImportSamplePlanWithDigicamControl)
{
auto digicam_control_items = std::vector<MissionRaw::MissionItem>{
{0,
MAV_FRAME_MISSION,
MAV_CMD_DO_DIGICAM_CONTROL,
1, // current
1, // autocontinue
1,
0,
0,
0,
1,
0,
0,
MAV_MISSION_TYPE_MISSION}};

std::ifstream file{path_prefix("qgroundcontrol_sample_with_digicam_control.plan")};
ASSERT_TRUE(file);

std::stringstream buf;
buf << file.rdbuf();
file.close();

const auto result_pair = MissionImport::parse_json(buf.str(), Autopilot::Px4);
ASSERT_EQ(result_pair.first, MissionRaw::Result::Success);

EXPECT_EQ(digicam_control_items, result_pair.second.mission_items);
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
{
"fileType": "Plan",
"geoFence": {
"circles": [],
"polygons": [],
"version": 2
},
"groundStation": "LiniaGenerator",
"mission": {
"cruiseSpeed": 10.0,
"firmwareType": 3,
"globalPlanAltitudeMode": 1,
"hoverSpeed": 10.0,
"items": [
{
"autoContinue": true,
"command": 203,
"doJumpId": 7,
"frame": 2,
"params": [
1,
0,
0,
0,
1,
0,
0
],
"type": "SimpleItem",
"amslaltAboveTerrain": null,
"altitudeMode": null,
"altitude": null
}
],
"vehicleType": 2,
"plannedHomePosition": [
0.0,
0.0,
0.0
],
"version": 2
},
"rallyPoints": {
"points": [],
"version": 2
},
"version": 1
}