Support for gimbal v2 protocol

- add command to request a message
- add gimbal attitude message

mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE

first implementation of new vmount input MavlinkGimbalV2
- setup class
- decode gimbal_manager_set_attitude in ControlData

add gimbal information message

add gimbal manager information and vehicle command ack

mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION

mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION

remove mavlink cmd handling from vmount input MavlinkGimbalV2

complete gimbal manager:
- send out fake gimbal_device_information for dummy gimbals
- complete ROI handling with nudging

small fixes

fix typos

cleanup
- gimbal device information
- flags lock
- check sanity of string

add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE

stream GimbalDeviceAttitudeStatus for dummy gimbals
- add uROB gimbal_attitude_status
- fill status in vmount output_rc for dummy gimbals not able to send the
status themselves
- stream mavlink GimbalDeviceAttitudeStatus

better handle the request for gimbal infomation request

clean up

bring gimbal information back on vmount init

add new gimbal message to mavlink normal stream

fix publication of gimbal device information

rename gimbal_attitude_status to gimbal_device_attitude_status

stream gimbal_manager_status at 5Hz

mavlink: send information only on request

Sending the information message once on request should now work and we
don't need to keep publishing it.

mavlink: debug output for now

make sure to copy over control data

mavlink: add missing copyright header, pragma once

mavlink: address review comments

mavlink: handle stream not updated

Our answer does not just depend on whether the stream was found but
whether we actually were able to send out an update.

mavlink: remove outdated comment

vmount: add option for yaw stabilization only

The stabilize flag is used for gimbals which do not have an internal IMU
and need the autopilot's attitude in order to do stabilization. These
gimbals are probably quite rare by now but it makes sense to keep the
functionality given it can e.g. be used by simple servo gimbals for
sensors other than highres cameras.

The stabilize flag can also be re-used for gimbals which are capable of
stabilizing pitch and roll but not absolute yaw (e.g. locked to North).
For such gimbals we can now set the param MNT_DO_STAB to 2.

We still support configuring which axes are stabilized by the
MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not
recommended anymore.

vmount: fix incorrect check for bit flag

mavlink_messages: remove debug message

Signed-off-by: Claudio Micheli <claudio@auterion.com>

use device id

remove debug print

gimbal attitude fix mistake

clang tidy fix

split:
- gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude
- gimbal_information -> gimbal_device_informatio, gimbal_manager_information

add gimbal protocol messages to rtps msg ids

support set attitude for gimbal directly speaking mavlink

clean up gimbal urob messages

vmount: address a few small review comments

vmount: split output into v1 and v2 protocol

This way we can continue to support the MAVLink v1 protocol. Also, we
don't send the old vehicle commands when actually using the new v2
protocol.

vmount: config via ctor instead of duplicate param

vmount: use loop to poll all topics

Otherwise we might give up too soon and miss some data, or run too fast
based on commands that have nothing to do with the gimbal.

typhoon_h480: use gimbal v2 protocol, use yaw stab

Let's by default use the v2 protocol with typhoon_h480 and enable yaw
lock mode by stabilizing yaw.
This commit is contained in:
Martina Rivizzigno
2020-05-12 10:32:16 +02:00
committed by Daniel Agar
parent 46e75ebddb
commit 48b00ff678
26 changed files with 1221 additions and 70 deletions
+6
View File
@@ -66,6 +66,12 @@ set(msg_files
follow_target.msg
generator_status.msg
geofence_result.msg
gimbal_device_set_attitude.msg
gimbal_manager_set_attitude.msg
gimbal_device_attitude_status.msg
gimbal_device_information.msg
gimbal_manager_information.msg
gimbal_manager_status.msg
gps_dump.msg
gps_inject_data.msg
heater_status.msg
+18
View File
@@ -0,0 +1,18 @@
uint64 timestamp # time since system start (microseconds)
uint8 target_system
uint8 target_component
uint16 device_flags
uint16 DEVICE_FLAGS_RETRACT = 1
uint16 DEVICE_FLAGS_NEUTRAL = 2
uint16 DEVICE_FLAGS_ROLL_LOCK = 4
uint16 DEVICE_FLAGS_PITCH_LOCK = 8
uint16 DEVICE_FLAGS_YAW_LOCK = 16
float32[4] q
float32 angular_velocity_x
float32 angular_velocity_y
float32 angular_velocity_z
uint32 failure_flags
+27
View File
@@ -0,0 +1,27 @@
uint64 timestamp # time since system start (microseconds)
uint8[32] vendor_name
uint8[32] model_name
uint32 firmware_version
uint16 capability_flags
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512
uint32 GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024
float32 tilt_max # [rad]
float32 tilt_min # [rad]
float32 tilt_rate_max # [rad / s]
float32 pan_max # [rad]
float32 pan_min # [rad]
float32 pan_rate_max # [rad / s]
+17
View File
@@ -0,0 +1,17 @@
uint64 timestamp # time since system start (microseconds)
uint8 target_system
uint8 target_component
uint16 flags
uint32 GIMBAL_DEVICE_FLAGS_RETRACT = 1
uint32 GIMBAL_DEVICE_FLAGS_NEUTRAL = 2
uint32 GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4
uint32 GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8
uint32 GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16
float32[4] q
float32 angular_velocity_x
float32 angular_velocity_y
float32 angular_velocity_z
+13
View File
@@ -0,0 +1,13 @@
uint64 timestamp # time since system start (microseconds)
uint32 capability_flags
uint8 gimbal_device_id
float32 tilt_max # [rad]
float32 tilt_min # [rad]
float32 tilt_rate_max # [rad / s]
float32 pan_max # [rad]
float32 pan_min # [rad]
float32 pan_rate_max # [rad / s]
+23
View File
@@ -0,0 +1,23 @@
uint64 timestamp # time since system start (microseconds)
uint8 target_system
uint8 target_component
uint32 GIMBAL_MANAGER_FLAGS_RETRACT = 1
uint32 GIMBAL_MANAGER_FLAGS_NEUTRAL = 2
uint32 GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4
uint32 GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8
uint32 GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16
uint32 GIMBAL_MANAGER_FLAGS_ANGULAR_VELOCITY_RELATIVE_TO_FOCAL_LENGTH = 1048576
uint32 GIMBAL_MANAGER_FLAGS_NUDGE = 2097152
uint32 GIMBAL_MANAGER_FLAGS_OVERRIDE = 4194304
uint32 GIMBAL_MANAGER_FLAGS_NONE = 8388608
uint32 flags
uint8 gimbal_device_id
float32[4] q
float32 angular_velocity_x
float32 angular_velocity_y
float32 angular_velocity_z
+4
View File
@@ -0,0 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 flags
uint8 gimbal_device_id
+12
View File
@@ -315,6 +315,18 @@ rtps:
id: 149
- msg: heater_status
id: 150
- msg: gimbal_device_attitude_status
id: 151
- msg: gimbal_device_information
id: 152
- msg: gimbal_device_set_attitude
id: 153
- msg: gimbal_manager_information
id: 154
- msg: gimbal_manager_set_attitude
id: 155
- msg: gimbal_manager_status
id: 156
########## multi topics: begin ##########
- msg: actuator_controls_0
id: 170
+4
View File
@@ -66,12 +66,16 @@ uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 ==
uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty|
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal
uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)|
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm|
uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes
uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX|
uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message
uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_ATTITUDE = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal attitude
uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data
uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data