Skip to content
This repository was archived by the owner on Apr 13, 2021. It is now read-only.

Commit cd192c7

Browse files
committed
Release 3.0
1 parent 3f02ca2 commit cd192c7

10 files changed

+2746
-1817
lines changed

LICENSE

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
Copyright (c) 2017, SPH Engineering
1+
Copyright (c) 2018, Smart Projects Holdings Ltd
22
All rights reserved.
33

44
Redistribution and use in source and binary forms, with or without
@@ -8,14 +8,14 @@ modification, are permitted provided that the following conditions are met:
88
* Redistributions in binary form must reproduce the above copyright
99
notice, this list of conditions and the following disclaimer in the
1010
documentation and/or other materials provided with the distribution.
11-
* Neither the name of the SPH ENGINEERING nor the
11+
* Neither the name of the SMART PROJECTS HOLDINGS nor the
1212
names of its contributors may be used to endorse or promote products
1313
derived from this software without specific prior written permission.
1414

1515
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
1616
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
1717
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18-
DISCLAIMED. IN NO EVENT SHALL SPH ENGINEERING BE LIABLE FOR ANY
18+
DISCLAIMED. IN NO EVENT SHALL SMART PROJECTS HOLDINGS BE LIABLE FOR ANY
1919
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
2020
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
2121
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND

doc/pages/user_guide.dox

+88-28
Original file line numberDiff line numberDiff line change
@@ -53,14 +53,7 @@ Supported vehicle types:
5353
- VTOL
5454

5555
Supported Ardupilot firmware versions:
56-
- 3.0
57-
- 3.1.x
58-
- 3.2.x
59-
- 3.3.x
60-
61-
Supported hardware platforms:
62-
- APM
63-
- Pixhawk
56+
- Any version starting from 3.0.0 and up to 3.6.0
6457

6558
@note When working with VTOL vehicles make sure the Q_MAV_TYPE correctly.
6659

@@ -73,24 +66,21 @@ Flight plan element / action | Support | Notes
7366
-----------------------------|---------|---------
7467
Change speed | Partial | Changing of flight speed during the mission may work only on latest 3.3.x firmware.
7568
Panorama | Partial | Only clock-wise movement is supported due to Ardupilot firmware bug. UgCS provides correct angle values according to Mavlink specification.
76-
Set camera mode | Partial | Only photo mode is supported. |
77-
Set camera by time | Partial | "First shot delay" parameter is not supported. |
78-
Set camera by distance | Partial | Only "Distance" parameter is supported. |
69+
Set camera mode | Partial | Only photo mode is supported. See @ref camera_trigger |
70+
Set camera by time | Partial | "First shot delay" parameter is not supported. See note below. |
71+
Set camera by distance | Partial | Only "Distance" parameter is supported. See note below. |
7972
Set camera attitude | No | |
8073
Set POI | Yes | |
8174
Change yaw | Yes | |
8275

83-
__Camera control__
84-
85-
For using camera you should set up necessary parameters in ArduPilot native
86-
software according to your hardware configuration. See also @ref camera_control_params
87-
- VSM configuration should match your copter configuration. See ArduCopter
88-
manual for details.
76+
@note __Camera series by time and by distance__<br>
77+
When mission includes a camera series (by time or by distance) action and mission flight is interrupted by issuing any command that interferes with mission (eg. Hold, Click&Go, RTH) during active camera series then
78+
triggering will stop until vehicle reaches the next waypoint with camera trigger action.
8979

90-
For example, in MissionPlanner the camera set up can be done in "Initial setup"
91-
page "Optional hardware/Camera gimbal/Shutter" section. Select the channel your
92-
shutter is connected to and set other parameters depending on your shutter
93-
control hardware.
80+
@note __Camera series by distance on ArduCopter prior version 3.6__<br>
81+
When mission includes a camera series by distance action and mission flight is interrupted by issuing any command that interferes with mission (eg. Hold, Click&Go, RTH) during active camera series then
82+
triggering will go on until "Continue" command is issued and vehicle reaches the next waypoint without camera trigger action.
83+
This is because of Ardupilot limitation which does not allow to stop camera triggering via standalone command.
9484

9585
@section altitude Altitude
9686

@@ -134,6 +124,8 @@ Vehicle behavior after returning at Home Location depends on on the configuratio
134124
- RTL_ALT_FINAL == 0: Vehicle will land automatically
135125
- RTL_ALT_FINAL > 0: Vehicle will descend to given altitude (in centimeters) and hover there waiting for user control.
136126

127+
The RTL_ALT_FINAL can be overridden in config file. See @ref rtl_alt_final.
128+
137129
@note RTL_ALT_FINAL parameter can be set using MissionPlanner software.
138130

139131

@@ -148,12 +140,41 @@ MANUALMODE | Yes | Sets _Manual_ mode. It's @b LOITER for multicopter f
148140
CLICK & GO | Yes | Sets _Click & Go_ (single waypoint) mode. |
149141
JOYSTICK | Yes | Sets _Joystick mode_. See also @ref joystick below. |
150142
HOLD | Yes | Pause mission execution. The drone will loiter at its current position. |
151-
CONTINUE | Yes | Continue with mission execution from next waypoint. Works from _Manual_, Joystick_ and _Click&Go_ modes.|
143+
CONTINUE | Yes | Continue with mission execution from next waypoint. Works from _Manual_, _Joystick_ and _Click&Go_ modes. If mission is already completed then vehicle will restart the mission.|
152144
RETURN HOME | Yes | Vehicle will return to home location. See also @ref home_location. |
153145
TAKEOFF | No | |
154146
LAND | Yes | |
155147
EMERGENCYLAND | No | |
156-
CAMERA_TRIGGER | No | |
148+
CAMERA_TRIGGER | Yes | See @ref camera_trigger for details|
149+
150+
@section camera_trigger Camera trigger command
151+
152+
There are two (mutually exclusive) ways to trigger camera on Ardupilot.
153+
154+
1) By default camera triggering done via DO_DIGICAM_CONTROL command.<br>
155+
This allows trigger by distance (typically used in aerial photo missions) and single shot. Trigger by time WP action is not possible with this command.<br>
156+
Camera interface must be configured via MissionPlanner or via "vehicle.ardupilot.parameter" settings before this command can be used.
157+
It is assumed that the vehicle is configured in "servo" mode (not "relay") for camera triggering.<br>
158+
Make sure that SERVO*_FUNCTION is set to 10 (camera trigger).
159+
Please refer to Ardupilot manual for details at http://ardupilot.org/copter/docs/common-camera-shutter-with-servo.html#shutter-configuration-with-pixhawk.
160+
161+
2) If camera trigger by time in mission is required then it should be specially configured via vehicle.ardupilot.camera_servo_idx parameter in vsm-ardupilot.conf.<br>
162+
For configuration parameters see @ref camera_control_params.<br>
163+
In this case camera is triggered via DO_REPEAT_SERVO command.
164+
This allows trigger by time and single shot. Trigger by distance WP action is not possible with this command.<br>
165+
When camera trigger command is issued then the specified servo is moved to the value specified by
166+
camera_servo_pwm and held there for the half of the specified interval. The servo then moves back to
167+
the value specified by the corresponding RC<camera_servo_idx>_TRIM parameter.
168+
Make sure that SERVO<camera_servo_idx>_FUNCTION is set to 0 (servo controlled by mission).
169+
Both parameters RC_TRIM and SERVO_FUNCTION should be configured via MissionPlanner or via "vehicle.ardupilot.parameter" settings.
170+
171+
3) Usage of both camera trigger actions "by time" and "by distance" in the same mission is not supported.
172+
173+
@section adsb_rx ADSB receiver support
174+
175+
Ardupilot supports connection with <a href="http://www.uavionix.com/products/pingrx">PingRX ADS-B receiver</a> from uAvionix.
176+
Please refer to <a href="http://ardupilot.org/copter/docs/common-ads-b-receiver.html">Ardupilot docs</a> for details on hardware setup.
177+
UgCS will receive the ADSB messages from autopilot and show detected vehicles in client GUI.
157178

158179
@section joystick Joystick support
159180

@@ -314,24 +335,25 @@ be visible to the UgCS.
314335

315336
@subsection camera_control_params Camera control parameters
316337

317-
Mandatory. Read Ardupilot manual about camera triggering configuration to
318-
understand these parameters. It is assumed that the vehicle is configured
319-
in "servo" mode (not "relay") for camera triggering.
338+
Camera trigger parameters. See also @ref camera_trigger.
320339

321340
- @b Name: vehicle.ardupilot.camera_servo_idx
341+
- @b Default: None. camera trigger is controlled via DO_DIGICAM_CONTROL command.
322342
- @b Description: Index of the servo to use for camera triggering.
323-
- @b Example:
343+
- @b Example (Use 8th servo output as camera trigger):
324344

325345
vehicle.ardupilot.camera_servo_idx = 8
326346

327347
- @b Name: vehicle.ardupilot.camera_servo_pwm
348+
- @b Default: Value from CAM_SERVO_ON parameter.
328349
- @b Description: PWM value to set for camera triggering servo when taking photo.
329350
- @b Example:
330351

331352
vehicle.ardupilot.camera_servo_pwm = 1900
332353

333354
- @b Name: vehicle.ardupilot.camera_servo_time
334-
- @b Description: Time to hold camera servo at the specified PWM when triggering single photo in seconds.
355+
- @b Default: Value from CAM_DURATION parameter.
356+
- @b Description: Time to hold camera servo at the specified PWM when triggering single photo in seconds. After that time servo will return to the RC<camera_servo_idx>_TRIM value. This value is used only in single shot command. WP action camera_trigger_by_time provides its own interval.
335357
- @b Example:
336358

337359
vehicle.ardupilot.camera_servo_time = 1.0
@@ -374,6 +396,31 @@ Rate of 1 produces ~350 bytes/sec of telemetry traffic.
374396

375397
vehicle.ardupilot.telemetry_rate = 1
376398

399+
@subsection ignore_speed Ignore route speed settings
400+
401+
Use this to disable all speed changes defined in route. Vehicle will fly with default speed the whole route.
402+
403+
- @b Required: No.
404+
- @b Supported @b values: yes, no
405+
- @b Default: no
406+
- @b Example:
407+
408+
vehicle.ardupilot.ignore_speed_in_route = yes
409+
410+
@subsection mavlink_injection Mavlink message injection
411+
412+
Ardupilot VSM can receive mavlink packets and forward them to the vehicle if vehicle with specified target_id is connected. It can be used to send GPS RTK corrections to vehicles.
413+
If message has no target_id or traget_id is 0 then it is sent to all connected vehicles.
414+
Supported messages are: COMMAND_LONG, COMMAND_INT, GPS_INJECT_DATA and GPS_RTCM_DATA.
415+
The prefix mavlink_injection supports all the same syntax as "connection" prefix.
416+
417+
- @b Required: No.
418+
- @b Supported @b values: Same as those for connection prefix.
419+
- @b Default: Not set.
420+
- @b Example:
421+
422+
mavlink_injection.udp_any.1.local_port = 44444
423+
377424
@subsection disarm_delay DISARM_DELAY parameter
378425

379426
- @b Required: No.
@@ -383,4 +430,17 @@ Rate of 1 produces ~350 bytes/sec of telemetry traffic.
383430
- @b Example:
384431

385432
vehicle.ardupilot.parameter.DISARM_DELAY = 5
433+
434+
@subsection rtl_alt_final RTL_ALT_FINAL parameter
435+
436+
- @b Required: No.
437+
- @b Supported @b values: Any positive integer
438+
- @b Default: Do not set
439+
- @b Unit: centimeter
440+
- @b Description: Set the final altitude in cm the vehicle will hover at after "Return To Home".
441+
Vehicle will land if set to 0.
442+
- @b Example: Hover at 5m altitude after RTH.
443+
444+
vehicle.ardupilot.parameter.RTL_ALT_FINAL = 500
445+
386446
*/

include/adsb_aircraft.h

+37
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
// Copyright (c) 2018, Smart Projects Holdings Ltd
2+
// All rights reserved.
3+
// See LICENSE file for license details.
4+
5+
// Aircraft class implements vehicle reported by ADSB receiver.
6+
// Each newly discovered ICAO code instantiates this object.
7+
// Adsb_vehicle has all ADSB related telemetry fields predefined.
8+
// Derived class only needs to populate them.
9+
10+
#ifndef _ADSB_AIRCRAFT_H_
11+
#define _ADSB_AIRCRAFT_H_
12+
13+
#include <ugcs/vsm/adsb_vehicle.h>
14+
#include <ugcs/vsm/mavlink.h>
15+
16+
class Adsb_aircraft: public Adsb_vehicle
17+
{
18+
DEFINE_COMMON_CLASS(Adsb_aircraft, Adsb_vehicle)
19+
20+
public:
21+
Adsb_aircraft(uint32_t icao) : Adsb_vehicle(icao) {}
22+
23+
// On_message processes ADSB_VEHICLE message and populates the telemetry fields.
24+
// With Ping receiver it's simple, it reports each aircraft in separate mavlink message.
25+
void
26+
On_message(ugcs::vsm::mavlink::Message<ugcs::vsm::mavlink::MESSAGE_ID::ADSB_VEHICLE>::Ptr message);
27+
28+
// Return seconds passed since last valid message about this vehicle was received.
29+
std::chrono::seconds
30+
Time_since_last_update();
31+
32+
private:
33+
// When was the last data for this vehicle was received
34+
std::chrono::time_point<std::chrono::steady_clock> last_update_time;
35+
};
36+
37+
#endif /* _ADSB_AIRCRAFT_H_ */

0 commit comments

Comments
 (0)