|
7 | 7 | #include <mavsdk/plugins/camera/camera.h> |
8 | 8 | #include <mavsdk/plugins/camera_server/camera_server.h> |
9 | 9 |
|
10 | | -/* |
11 | | - This example runs a MAVLink "camera" utilizing the MAVSDK server plugins |
12 | | - on a separate thread. This uses two MAVSDK instances, one GCS, one camera. |
13 | | -
|
14 | | - The main thread acts as a GCS and reads telemetry, parameters, transmits across |
15 | | - a mission, clears the mission, arms the vehicle and then triggers a vehicle takeoff. |
16 | | -
|
17 | | - The camera thread handles all the servers and triggers callbacks, publishes telemetry, |
18 | | - handles and stores parameters, prints received missions and sets the vehicle height to 10m on |
19 | | - successful takeoff request. |
20 | | -*/ |
21 | | - |
22 | 10 | using namespace mavsdk; |
23 | 11 |
|
24 | 12 | using std::chrono::duration_cast; |
@@ -54,17 +42,7 @@ int main(int argc, char** argv) |
54 | 42 |
|
55 | 43 | all_camera_servers.insert({system->get_system_id(), camera_server}); |
56 | 44 |
|
57 | | - camera_server->set_information({ |
58 | | - .vendor_name = "MAVSDK", |
59 | | - .model_name = "Example Camera Server", |
60 | | - .focal_length_mm = 3.0, |
61 | | - .horizontal_sensor_size_mm = 3.68, |
62 | | - .vertical_sensor_size_mm = 2.76, |
63 | | - .horizontal_resolution_px = 3280, |
64 | | - .vertical_resolution_px = 2464, |
65 | | - }); |
66 | | - |
67 | | - camera_server->set_in_progress(false); |
| 45 | + // First add all subscriptions. This defines the camera capabilities. |
68 | 46 |
|
69 | 47 | camera_server->subscribe_take_photo( |
70 | 48 | [camera_server, &all_camera_servers](CameraServer::Result result, int32_t index) { |
@@ -99,6 +77,22 @@ int main(int argc, char** argv) |
99 | 77 | } |
100 | 78 | }); |
101 | 79 |
|
| 80 | + // Then set the initial state of everything. |
| 81 | + |
| 82 | + camera_server->set_in_progress(false); |
| 83 | + |
| 84 | + // Finally call set_information() to "activate" the camera plugin. |
| 85 | + |
| 86 | + camera_server->set_information({ |
| 87 | + .vendor_name = "MAVSDK", |
| 88 | + .model_name = "Example Camera Server", |
| 89 | + .focal_length_mm = 3.0, |
| 90 | + .horizontal_sensor_size_mm = 3.68, |
| 91 | + .vertical_sensor_size_mm = 2.76, |
| 92 | + .horizontal_resolution_px = 3280, |
| 93 | + .vertical_resolution_px = 2464, |
| 94 | + }); |
| 95 | + |
102 | 96 | std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") |
103 | 97 | << " system ID " << +system->get_system_id() << std::endl; |
104 | 98 | } |
|
0 commit comments