Skip to content
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

Add acceptance_radius back to MissionItem #1443

Merged
merged 9 commits into from
May 28, 2021
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
2 changes: 1 addition & 1 deletion proto
25 changes: 17 additions & 8 deletions src/integration_tests/mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ static Mission::MissionItem add_mission_item(
float gimbal_pitch_deg,
float gimbal_yaw_deg,
float loiter_time_s,
Mission::MissionItem::CameraAction camera_action);
Mission::MissionItem::CameraAction camera_action,
float acceptance_radius_m);

static void pause_and_resume(std::shared_ptr<Mission> mission);

Expand Down Expand Up @@ -101,7 +102,8 @@ void test_mission(
20.0f,
60.0f,
NAN,
Mission::MissionItem::CameraAction::None));
Mission::MissionItem::CameraAction::None,
0.5f));

mission_plan.mission_items.push_back(add_mission_item(
47.398241338125118,
Expand All @@ -112,7 +114,8 @@ void test_mission(
0.0f,
-60.0f,
5.0f,
Mission::MissionItem::CameraAction::TakePhoto));
Mission::MissionItem::CameraAction::TakePhoto,
4.0f));

mission_plan.mission_items.push_back(add_mission_item(
47.398139363821485,
Expand All @@ -123,7 +126,8 @@ void test_mission(
-46.0f,
0.0f,
NAN,
Mission::MissionItem::CameraAction::StartVideo));
Mission::MissionItem::CameraAction::StartVideo,
4.0f));

mission_plan.mission_items.push_back(add_mission_item(
47.398058617228855,
Expand All @@ -134,7 +138,8 @@ void test_mission(
-90.0f,
30.0f,
NAN,
Mission::MissionItem::CameraAction::StopVideo));
Mission::MissionItem::CameraAction::StopVideo,
0.5f));

mission_plan.mission_items.push_back(add_mission_item(
47.398100366082858,
Expand All @@ -145,7 +150,8 @@ void test_mission(
-45.0f,
-30.0f,
NAN,
Mission::MissionItem::CameraAction::StartPhotoInterval));
Mission::MissionItem::CameraAction::StartPhotoInterval,
0.5f));

mission_plan.mission_items.push_back(add_mission_item(
47.398001890458097,
Expand All @@ -156,7 +162,8 @@ void test_mission(
0.0f,
0.0f,
NAN,
Mission::MissionItem::CameraAction::StopPhotoInterval));
Mission::MissionItem::CameraAction::StopPhotoInterval,
0.5f));
}

mission->set_return_to_launch_after_mission(true);
Expand Down Expand Up @@ -279,7 +286,8 @@ Mission::MissionItem add_mission_item(
float gimbal_pitch_deg,
float gimbal_yaw_deg,
float loiter_time_s,
Mission::MissionItem::CameraAction camera_action)
Mission::MissionItem::CameraAction camera_action,
float acceptance_radius_m)
{
Mission::MissionItem new_item{};
new_item.latitude_deg = latitude_deg;
Expand All @@ -291,6 +299,7 @@ Mission::MissionItem add_mission_item(
new_item.gimbal_yaw_deg = gimbal_yaw_deg;
new_item.loiter_time_s = loiter_time_s;
new_item.camera_action = camera_action;
new_item.acceptance_radius_m = acceptance_radius_m;

// In order to test setting the interval, add it here.
if (camera_action == Mission::MissionItem::CameraAction::StartPhotoInterval) {
Expand Down
1 change: 1 addition & 0 deletions src/integration_tests/mission_change_speed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ add_waypoint(double latitude_deg, double longitude_deg, float relative_altitude_
new_item.longitude_deg = longitude_deg;
new_item.relative_altitude_m = relative_altitude_m;
new_item.speed_m_s = speed_m_s;
new_item.acceptance_radius_m = 1.0f;
return new_item;
}

Expand Down
1 change: 1 addition & 0 deletions src/integration_tests/mission_transfer_lossy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ std::vector<Mission::MissionItem> create_mission_items()
new_item.longitude_deg = 8.5456490218639658 + (i * 1e-6);
new_item.relative_altitude_m = 10.0f + (i * 0.2f);
new_item.speed_m_s = 5.0f + (i * 0.1f);
new_item.acceptance_radius_m = 2.0f;
mission_items.push_back(new_item);
}
return mission_items;
Expand Down
168 changes: 96 additions & 72 deletions src/mavsdk_server/src/generated/mission/mission.pb.cc

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Loading