Skip to content

Commit eae375e

Browse files
committed
1 parent e464ff8 commit eae375e

27 files changed

+489
-322
lines changed

MAVLinkPacket.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -346,8 +346,6 @@ public MAVLinkMessage unpack() {
346346
return new msg_param_map_rc(this);
347347
case msg_mission_request_int.MAVLINK_MSG_ID_MISSION_REQUEST_INT:
348348
return new msg_mission_request_int(this);
349-
case msg_mission_checksum.MAVLINK_MSG_ID_MISSION_CHECKSUM:
350-
return new msg_mission_checksum(this);
351349
case msg_safety_set_allowed_area.MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA:
352350
return new msg_safety_set_allowed_area(this);
353351
case msg_safety_allowed_area.MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA:
@@ -702,6 +700,8 @@ public MAVLinkMessage unpack() {
702700
return new msg_available_modes(this);
703701
case msg_current_mode.MAVLINK_MSG_ID_CURRENT_MODE:
704702
return new msg_current_mode(this);
703+
case msg_available_modes_monitor.MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
704+
return new msg_available_modes_monitor(this);
705705
case msg_target_absolute.MAVLINK_MSG_ID_TARGET_ABSOLUTE:
706706
return new msg_target_absolute(this);
707707
case msg_target_relative.MAVLINK_MSG_ID_TARGET_RELATIVE:

common/msg_camera_information.java

+34-23
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
public class msg_camera_information extends MAVLinkMessage {
1919

2020
public static final int MAVLINK_MSG_ID_CAMERA_INFORMATION = 259;
21-
public static final int MAVLINK_MSG_LENGTH = 235;
21+
public static final int MAVLINK_MSG_LENGTH = 236;
2222
private static final long serialVersionUID = MAVLINK_MSG_ID_CAMERA_INFORMATION;
2323

2424

@@ -30,30 +30,30 @@ public class msg_camera_information extends MAVLinkMessage {
3030
public long time_boot_ms;
3131

3232
/**
33-
* Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
33+
* Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
3434
*/
35-
@Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)")
35+
@Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.")
3636
@Units("")
3737
public long firmware_version;
3838

3939
/**
40-
* Focal length
40+
* Focal length. Use NaN if not known.
4141
*/
42-
@Description("Focal length")
42+
@Description("Focal length. Use NaN if not known.")
4343
@Units("mm")
4444
public float focal_length;
4545

4646
/**
47-
* Image sensor size horizontal
47+
* Image sensor size horizontal. Use NaN if not known.
4848
*/
49-
@Description("Image sensor size horizontal")
49+
@Description("Image sensor size horizontal. Use NaN if not known.")
5050
@Units("mm")
5151
public float sensor_size_h;
5252

5353
/**
54-
* Image sensor size vertical
54+
* Image sensor size vertical. Use NaN if not known.
5555
*/
56-
@Description("Image sensor size vertical")
56+
@Description("Image sensor size vertical. Use NaN if not known.")
5757
@Units("mm")
5858
public float sensor_size_v;
5959

@@ -65,23 +65,23 @@ public class msg_camera_information extends MAVLinkMessage {
6565
public long flags;
6666

6767
/**
68-
* Horizontal image resolution
68+
* Horizontal image resolution. Use 0 if not known.
6969
*/
70-
@Description("Horizontal image resolution")
70+
@Description("Horizontal image resolution. Use 0 if not known.")
7171
@Units("pix")
7272
public int resolution_h;
7373

7474
/**
75-
* Vertical image resolution
75+
* Vertical image resolution. Use 0 if not known.
7676
*/
77-
@Description("Vertical image resolution")
77+
@Description("Vertical image resolution. Use 0 if not known.")
7878
@Units("pix")
7979
public int resolution_v;
8080

8181
/**
82-
* Camera definition version (iteration)
82+
* Camera definition version (iteration). Use 0 if not known.
8383
*/
84-
@Description("Camera definition version (iteration)")
84+
@Description("Camera definition version (iteration). Use 0 if not known.")
8585
@Units("")
8686
public int cam_definition_version;
8787

@@ -100,19 +100,26 @@ public class msg_camera_information extends MAVLinkMessage {
100100
public short model_name[] = new short[32];
101101

102102
/**
103-
* Reserved for a lens ID
103+
* Reserved for a lens ID. Use 0 if not known.
104104
*/
105-
@Description("Reserved for a lens ID")
105+
@Description("Reserved for a lens ID. Use 0 if not known.")
106106
@Units("")
107107
public short lens_id;
108108

109109
/**
110-
* Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated.
110+
* Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
111111
*/
112-
@Description("Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated.")
112+
@Description("Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.")
113113
@Units("")
114114
public byte cam_definition_uri[] = new byte[140];
115115

116+
/**
117+
* Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
118+
*/
119+
@Description("Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.")
120+
@Units("")
121+
public short gimbal_device_id;
122+
116123

117124
/**
118125
* Generates the payload for a mavlink message for a message of this type
@@ -152,6 +159,7 @@ public MAVLinkPacket pack() {
152159

153160

154161
if (isMavlink2) {
162+
packet.payload.putUnsignedByte(gimbal_device_id);
155163

156164
}
157165
return packet;
@@ -193,6 +201,7 @@ public void unpack(MAVLinkPayload payload) {
193201

194202

195203
if (isMavlink2) {
204+
this.gimbal_device_id = payload.getUnsignedByte();
196205

197206
}
198207
}
@@ -207,7 +216,7 @@ public msg_camera_information() {
207216
/**
208217
* Constructor for a new message, initializes msgid and all payload variables
209218
*/
210-
public msg_camera_information( long time_boot_ms, long firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, long flags, int resolution_h, int resolution_v, int cam_definition_version, short[] vendor_name, short[] model_name, short lens_id, byte[] cam_definition_uri) {
219+
public msg_camera_information( long time_boot_ms, long firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, long flags, int resolution_h, int resolution_v, int cam_definition_version, short[] vendor_name, short[] model_name, short lens_id, byte[] cam_definition_uri, short gimbal_device_id) {
211220
this.msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
212221

213222
this.time_boot_ms = time_boot_ms;
@@ -223,13 +232,14 @@ public msg_camera_information( long time_boot_ms, long firmware_version, float f
223232
this.model_name = model_name;
224233
this.lens_id = lens_id;
225234
this.cam_definition_uri = cam_definition_uri;
235+
this.gimbal_device_id = gimbal_device_id;
226236

227237
}
228238

229239
/**
230240
* Constructor for a new message, initializes everything
231241
*/
232-
public msg_camera_information( long time_boot_ms, long firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, long flags, int resolution_h, int resolution_v, int cam_definition_version, short[] vendor_name, short[] model_name, short lens_id, byte[] cam_definition_uri, int sysid, int compid, boolean isMavlink2) {
242+
public msg_camera_information( long time_boot_ms, long firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, long flags, int resolution_h, int resolution_v, int cam_definition_version, short[] vendor_name, short[] model_name, short lens_id, byte[] cam_definition_uri, short gimbal_device_id, int sysid, int compid, boolean isMavlink2) {
233243
this.msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
234244
this.sysid = sysid;
235245
this.compid = compid;
@@ -248,6 +258,7 @@ public msg_camera_information( long time_boot_ms, long firmware_version, float f
248258
this.model_name = model_name;
249259
this.lens_id = lens_id;
250260
this.cam_definition_uri = cam_definition_uri;
261+
this.gimbal_device_id = gimbal_device_id;
251262

252263
}
253264

@@ -294,13 +305,13 @@ public String getCam_Definition_Uri() {
294305
return buf.toString();
295306

296307
}
297-
308+
298309
/**
299310
* Returns a string with the MSG name and data
300311
*/
301312
@Override
302313
public String toString() {
303-
return "MAVLINK_MSG_ID_CAMERA_INFORMATION - sysid:"+sysid+" compid:"+compid+" time_boot_ms:"+time_boot_ms+" firmware_version:"+firmware_version+" focal_length:"+focal_length+" sensor_size_h:"+sensor_size_h+" sensor_size_v:"+sensor_size_v+" flags:"+flags+" resolution_h:"+resolution_h+" resolution_v:"+resolution_v+" cam_definition_version:"+cam_definition_version+" vendor_name:"+vendor_name+" model_name:"+model_name+" lens_id:"+lens_id+" cam_definition_uri:"+cam_definition_uri+"";
314+
return "MAVLINK_MSG_ID_CAMERA_INFORMATION - sysid:"+sysid+" compid:"+compid+" time_boot_ms:"+time_boot_ms+" firmware_version:"+firmware_version+" focal_length:"+focal_length+" sensor_size_h:"+sensor_size_h+" sensor_size_v:"+sensor_size_v+" flags:"+flags+" resolution_h:"+resolution_h+" resolution_v:"+resolution_v+" cam_definition_version:"+cam_definition_version+" vendor_name:"+vendor_name+" model_name:"+model_name+" lens_id:"+lens_id+" cam_definition_uri:"+cam_definition_uri+" gimbal_device_id:"+gimbal_device_id+"";
304315
}
305316

306317
/**

common/msg_gimbal_device_attitude_status.java

+28-17
Original file line numberDiff line numberDiff line change
@@ -13,26 +13,26 @@
1313
import com.MAVLink.Messages.Description;
1414

1515
/**
16-
* Message reporting the status of a gimbal device.
17-
This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz).
18-
For the angles encoded in the quaternion and the angular velocities holds:
19-
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame).
20-
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame).
21-
If neither of these flags are set, then (for backwards compatibility) it holds:
22-
If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame),
23-
else they are relative to the vehicle heading (vehicle frame).
24-
Other conditions of the flags are not allowed.
25-
The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as
16+
* Message reporting the status of a gimbal device.
17+
This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz).
18+
For the angles encoded in the quaternion and the angular velocities holds:
19+
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame).
20+
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame).
21+
If neither of these flags are set, then (for backwards compatibility) it holds:
22+
If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame),
23+
else they are relative to the vehicle heading (vehicle frame).
24+
Other conditions of the flags are not allowed.
25+
The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as
2626
q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN).
27-
If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set,
27+
If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set,
2828
then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored.
29-
New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME,
29+
New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME,
3030
and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN.
3131
*/
3232
public class msg_gimbal_device_attitude_status extends MAVLinkMessage {
3333

3434
public static final int MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS = 285;
35-
public static final int MAVLINK_MSG_LENGTH = 48;
35+
public static final int MAVLINK_MSG_LENGTH = 49;
3636
private static final long serialVersionUID = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS;
3737

3838

@@ -113,6 +113,13 @@ public class msg_gimbal_device_attitude_status extends MAVLinkMessage {
113113
@Units("rad/s")
114114
public float delta_yaw_velocity;
115115

116+
/**
117+
* This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
118+
*/
119+
@Description("This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.")
120+
@Units("")
121+
public short gimbal_device_id;
122+
116123

117124
/**
118125
* Generates the payload for a mavlink message for a message of this type
@@ -142,6 +149,7 @@ public MAVLinkPacket pack() {
142149
if (isMavlink2) {
143150
packet.payload.putFloat(delta_yaw);
144151
packet.payload.putFloat(delta_yaw_velocity);
152+
packet.payload.putUnsignedByte(gimbal_device_id);
145153

146154
}
147155
return packet;
@@ -173,6 +181,7 @@ public void unpack(MAVLinkPayload payload) {
173181
if (isMavlink2) {
174182
this.delta_yaw = payload.getFloat();
175183
this.delta_yaw_velocity = payload.getFloat();
184+
this.gimbal_device_id = payload.getUnsignedByte();
176185

177186
}
178187
}
@@ -187,7 +196,7 @@ public msg_gimbal_device_attitude_status() {
187196
/**
188197
* Constructor for a new message, initializes msgid and all payload variables
189198
*/
190-
public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, long failure_flags, int flags, short target_system, short target_component, float delta_yaw, float delta_yaw_velocity) {
199+
public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, long failure_flags, int flags, short target_system, short target_component, float delta_yaw, float delta_yaw_velocity, short gimbal_device_id) {
191200
this.msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS;
192201

193202
this.time_boot_ms = time_boot_ms;
@@ -201,13 +210,14 @@ public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float an
201210
this.target_component = target_component;
202211
this.delta_yaw = delta_yaw;
203212
this.delta_yaw_velocity = delta_yaw_velocity;
213+
this.gimbal_device_id = gimbal_device_id;
204214

205215
}
206216

207217
/**
208218
* Constructor for a new message, initializes everything
209219
*/
210-
public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, long failure_flags, int flags, short target_system, short target_component, float delta_yaw, float delta_yaw_velocity, int sysid, int compid, boolean isMavlink2) {
220+
public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, long failure_flags, int flags, short target_system, short target_component, float delta_yaw, float delta_yaw_velocity, short gimbal_device_id, int sysid, int compid, boolean isMavlink2) {
211221
this.msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS;
212222
this.sysid = sysid;
213223
this.compid = compid;
@@ -224,6 +234,7 @@ public msg_gimbal_device_attitude_status( long time_boot_ms, float[] q, float an
224234
this.target_component = target_component;
225235
this.delta_yaw = delta_yaw;
226236
this.delta_yaw_velocity = delta_yaw_velocity;
237+
this.gimbal_device_id = gimbal_device_id;
227238

228239
}
229240

@@ -241,13 +252,13 @@ public msg_gimbal_device_attitude_status(MAVLinkPacket mavLinkPacket) {
241252
unpack(mavLinkPacket.payload);
242253
}
243254

244-
255+
245256
/**
246257
* Returns a string with the MSG name and data
247258
*/
248259
@Override
249260
public String toString() {
250-
return "MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS - sysid:"+sysid+" compid:"+compid+" time_boot_ms:"+time_boot_ms+" q:"+q+" angular_velocity_x:"+angular_velocity_x+" angular_velocity_y:"+angular_velocity_y+" angular_velocity_z:"+angular_velocity_z+" failure_flags:"+failure_flags+" flags:"+flags+" target_system:"+target_system+" target_component:"+target_component+" delta_yaw:"+delta_yaw+" delta_yaw_velocity:"+delta_yaw_velocity+"";
261+
return "MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS - sysid:"+sysid+" compid:"+compid+" time_boot_ms:"+time_boot_ms+" q:"+q+" angular_velocity_x:"+angular_velocity_x+" angular_velocity_y:"+angular_velocity_y+" angular_velocity_z:"+angular_velocity_z+" failure_flags:"+failure_flags+" flags:"+flags+" target_system:"+target_system+" target_component:"+target_component+" delta_yaw:"+delta_yaw+" delta_yaw_velocity:"+delta_yaw_velocity+" gimbal_device_id:"+gimbal_device_id+"";
251262
}
252263

253264
/**

0 commit comments

Comments
 (0)