Skip to content

Commit

Permalink
mission: add distance based triggering
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 28, 2021
1 parent 00290d6 commit 108a51a
Show file tree
Hide file tree
Showing 8 changed files with 134 additions and 59 deletions.
2 changes: 1 addition & 1 deletion proto
28 changes: 27 additions & 1 deletion src/integration_tests/mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void test_mission(
while (!telemetry->health_all_ok()) {
LogInfo() << "Waiting for system to be ready";
LogDebug() << "Health: " << telemetry->health();
std::this_thread::sleep_for(std::chrono::seconds(1));
std::this_thread::sleep_for(std::chrono::seconds(30));
}

LogInfo() << "System ready";
Expand Down Expand Up @@ -170,6 +170,32 @@ void test_mission(
Mission::MissionItem::CameraAction::StopPhotoInterval,
0.5f,
NAN));

mission_plan.mission_items.push_back(add_mission_item(
47.393,
8.544,
10.0f,
5.0f,
false,
-45.0f,
-30.0f,
NAN,
Mission::MissionItem::CameraAction::StartPhotoDistance,
0.5f,
0.0f));

mission_plan.mission_items.push_back(add_mission_item(
47.395,
8.542,
10.0f,
5.0f,
false,
0.0f,
0.0f,
NAN,
Mission::MissionItem::CameraAction::StopPhotoDistance,
0.5f,
NAN));
}

mission->set_return_to_launch_after_mission(true);
Expand Down
118 changes: 62 additions & 56 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.

8 changes: 7 additions & 1 deletion src/mavsdk_server/src/generated/mission/mission.pb.h

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

8 changes: 8 additions & 0 deletions src/mavsdk_server/src/plugins/mission/mission_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,10 @@ class MissionServiceImpl final : public rpc::mission::MissionService::Service {
return rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_START_VIDEO;
case mavsdk::Mission::MissionItem::CameraAction::StopVideo:
return rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_STOP_VIDEO;
case mavsdk::Mission::MissionItem::CameraAction::StartPhotoDistance:
return rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_START_PHOTO_DISTANCE;
case mavsdk::Mission::MissionItem::CameraAction::StopPhotoDistance:
return rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_STOP_PHOTO_DISTANCE;
}
}

Expand All @@ -79,6 +83,10 @@ class MissionServiceImpl final : public rpc::mission::MissionService::Service {
return mavsdk::Mission::MissionItem::CameraAction::StartVideo;
case rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_STOP_VIDEO:
return mavsdk::Mission::MissionItem::CameraAction::StopVideo;
case rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_START_PHOTO_DISTANCE:
return mavsdk::Mission::MissionItem::CameraAction::StartPhotoDistance;
case rpc::mission::MissionItem_CameraAction_CAMERA_ACTION_STOP_PHOTO_DISTANCE:
return mavsdk::Mission::MissionItem::CameraAction::StopPhotoDistance;
}
}

Expand Down
2 changes: 2 additions & 0 deletions src/plugins/mission/include/plugins/mission/mission.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ class Mission : public PluginBase {
StopPhotoInterval, /**< @brief Stop capturing photos at regular intervals. */
StartVideo, /**< @brief Start capturing video. */
StopVideo, /**< @brief Stop capturing video. */
StartPhotoDistance, /**< @brief Start capturing photos at regular distance. */
StopPhotoDistance, /**< @brief Stop capturing photos at regular distance. */
};

/**
Expand Down
4 changes: 4 additions & 0 deletions src/plugins/mission/mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,10 @@ std::ostream& operator<<(std::ostream& str, Mission::MissionItem::CameraAction c
return str << "Start Video";
case Mission::MissionItem::CameraAction::StopVideo:
return str << "Stop Video";
case Mission::MissionItem::CameraAction::StartPhotoDistance:
return str << "Start Photo Distance";
case Mission::MissionItem::CameraAction::StopPhotoDistance:
return str << "Stop Photo Distance";
default:
return str << "Unknown";
}
Expand Down
23 changes: 23 additions & 0 deletions src/plugins/mission/mission_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -443,6 +443,18 @@ MissionImpl::convert_to_int_items(const std::vector<MissionItem>& mission_items)
command = MAV_CMD_VIDEO_STOP_CAPTURE;
param1 = 0.0f; // all camera IDs
break;
case CameraAction::StartPhotoDistance:
command = MAV_CMD_DO_TRIGGER_CONTROL;
param1 = 1.0f; // enable
param2 = 0.0f; // don't reset
param3 = -1.0f; // don't pause
break;
case CameraAction::StopPhotoDistance:
command = MAV_CMD_DO_TRIGGER_CONTROL;
param1 = 0.0f; // disable
param2 = 0.0f; // don't reset
param3 = -1.0f; // don't pause
break;
default:
LogErr() << "Error: camera action not supported";
break;
Expand Down Expand Up @@ -609,6 +621,17 @@ std::pair<Mission::Result, Mission::MissionPlan> MissionImpl::convert_to_result_
} else if (int_item.command == MAV_CMD_VIDEO_STOP_CAPTURE) {
new_mission_item.camera_action = CameraAction::StopVideo;

} else if (int_item.command == MAV_CMD_DO_TRIGGER_CONTROL) {
if (static_cast<int>(int_item.param1) == 1) {
new_mission_item.camera_action = CameraAction::StartPhotoDistance;
} else if (static_cast<int>(int_item.param1) == 0) {
new_mission_item.camera_action = CameraAction::StopPhotoDistance;
} else {
LogWarn() << "Unknown trigger control mission item ignored";
result_pair.first = Mission::Result::Unsupported;
break;
}

} else if (int_item.command == MAV_CMD_DO_CHANGE_SPEED) {
if (int(int_item.param1) == 1 && int_item.param3 < 0 && int(int_item.param4) == 0) {
new_mission_item.speed_m_s = int_item.param2;
Expand Down

0 comments on commit 108a51a

Please sign in to comment.