Skip to content

Commit e464ff8

Browse files
committed
1 parent a1db853 commit e464ff8

21 files changed

+799
-138
lines changed

MAVLinkPacket.java

+4
Original file line numberDiff line numberDiff line change
@@ -702,6 +702,10 @@ public MAVLinkMessage unpack() {
702702
return new msg_available_modes(this);
703703
case msg_current_mode.MAVLINK_MSG_ID_CURRENT_MODE:
704704
return new msg_current_mode(this);
705+
case msg_target_absolute.MAVLINK_MSG_ID_TARGET_ABSOLUTE:
706+
return new msg_target_absolute(this);
707+
case msg_target_relative.MAVLINK_MSG_ID_TARGET_RELATIVE:
708+
return new msg_target_relative(this);
705709
case msg_wheel_distance.MAVLINK_MSG_ID_WHEEL_DISTANCE:
706710
return new msg_wheel_distance(this);
707711
case msg_winch_status.MAVLINK_MSG_ID_WINCH_STATUS:

common/msg_command_ack.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -37,16 +37,16 @@ public class msg_command_ack extends MAVLinkMessage {
3737
public short result;
3838

3939
/**
40-
* Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).
40+
* The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
4141
*/
42-
@Description("Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).")
43-
@Units("")
42+
@Description("The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.")
43+
@Units("%")
4444
public short progress;
4545

4646
/**
47-
* Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
47+
* Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate 'unused' or 'unknown').
4848
*/
49-
@Description("Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.")
49+
@Description("Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate 'unused' or 'unknown').")
5050
@Units("")
5151
public int result_param2;
5252

common/msg_command_int.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
import com.MAVLink.Messages.Description;
1414

1515
/**
16-
* Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG when sending positional data in params 5 and 6, as it allows for greater precision when sending latitudes/longitudes. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html
16+
* Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html
1717
*/
1818
public class msg_command_int extends MAVLinkMessage {
1919

common/msg_command_long.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
import com.MAVLink.Messages.Description;
1414

1515
/**
16-
* Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands where param 5 and param 6 contain latitude/longitude data, as sending these in floats can result in a significant loss of precision. COMMAND_LONG is required for commands that mandate float values in params 5 and 6. The command microservice is documented at https://mavlink.io/en/services/command.html
16+
* Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html
1717
*/
1818
public class msg_command_long extends MAVLinkMessage {
1919

common/msg_gimbal_manager_set_pitchyaw.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
import com.MAVLink.Messages.Description;
1414

1515
/**
16-
* High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.
16+
* Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation.
1717
*/
1818
public class msg_gimbal_manager_set_pitchyaw extends MAVLinkMessage {
1919

common/msg_mission_current.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ public class msg_mission_current extends MAVLinkMessage {
3434
public int seq;
3535

3636
/**
37-
* Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
37+
* Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
3838
*/
39-
@Description("Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.")
39+
@Description("Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.")
4040
@Units("")
4141
public int total;
4242

development/CRC.java

+4-2
Original file line numberDiff line numberDiff line change
@@ -240,8 +240,10 @@ public class CRC {
240240
MAVLINK_MESSAGE_CRCS.put(413, 77);
241241
MAVLINK_MESSAGE_CRCS.put(414, 109);
242242
MAVLINK_MESSAGE_CRCS.put(415, 161);
243-
MAVLINK_MESSAGE_CRCS.put(435, 94);
244-
MAVLINK_MESSAGE_CRCS.put(436, 151);
243+
MAVLINK_MESSAGE_CRCS.put(435, 134);
244+
MAVLINK_MESSAGE_CRCS.put(436, 193);
245+
MAVLINK_MESSAGE_CRCS.put(510, 245);
246+
MAVLINK_MESSAGE_CRCS.put(511, 28);
245247
MAVLINK_MESSAGE_CRCS.put(9000, 113);
246248
MAVLINK_MESSAGE_CRCS.put(9005, 117);
247249
MAVLINK_MESSAGE_CRCS.put(12900, 114);

development/msg_available_modes.java

+19-19
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ Each modes should only be emitted once (even if it is both standard and custom).
2323
public class msg_available_modes extends MAVLinkMessage {
2424

2525
public static final int MAVLINK_MSG_ID_AVAILABLE_MODES = 435;
26-
public static final int MAVLINK_MSG_LENGTH = 58;
26+
public static final int MAVLINK_MSG_LENGTH = 46;
2727
private static final long serialVersionUID = MAVLINK_MSG_ID_AVAILABLE_MODES;
2828

2929

@@ -34,6 +34,13 @@ public class msg_available_modes extends MAVLinkMessage {
3434
@Units("")
3535
public long custom_mode;
3636

37+
/**
38+
* Mode properties.
39+
*/
40+
@Description("Mode properties.")
41+
@Units("")
42+
public long properties;
43+
3744
/**
3845
* The total number of available modes for the current vehicle type.
3946
*/
@@ -55,19 +62,12 @@ public class msg_available_modes extends MAVLinkMessage {
5562
@Units("")
5663
public short standard_mode;
5764

58-
/**
59-
* System mode bitmap.
60-
*/
61-
@Description("System mode bitmap.")
62-
@Units("")
63-
public short base_mode;
64-
6565
/**
6666
* Name of custom mode, with null termination character. Should be omitted for standard modes.
6767
*/
6868
@Description("Name of custom mode, with null termination character. Should be omitted for standard modes.")
6969
@Units("")
70-
public byte mode_name[] = new byte[50];
70+
public byte mode_name[] = new byte[35];
7171

7272

7373
/**
@@ -82,10 +82,10 @@ public MAVLinkPacket pack() {
8282
packet.msgid = MAVLINK_MSG_ID_AVAILABLE_MODES;
8383

8484
packet.payload.putUnsignedInt(custom_mode);
85+
packet.payload.putUnsignedInt(properties);
8586
packet.payload.putUnsignedByte(number_modes);
8687
packet.payload.putUnsignedByte(mode_index);
8788
packet.payload.putUnsignedByte(standard_mode);
88-
packet.payload.putUnsignedByte(base_mode);
8989

9090
for (int i = 0; i < mode_name.length; i++) {
9191
packet.payload.putByte(mode_name[i]);
@@ -108,10 +108,10 @@ public void unpack(MAVLinkPayload payload) {
108108
payload.resetIndex();
109109

110110
this.custom_mode = payload.getUnsignedInt();
111+
this.properties = payload.getUnsignedInt();
111112
this.number_modes = payload.getUnsignedByte();
112113
this.mode_index = payload.getUnsignedByte();
113114
this.standard_mode = payload.getUnsignedByte();
114-
this.base_mode = payload.getUnsignedByte();
115115

116116
for (int i = 0; i < this.mode_name.length; i++) {
117117
this.mode_name[i] = payload.getByte();
@@ -133,32 +133,32 @@ public msg_available_modes() {
133133
/**
134134
* Constructor for a new message, initializes msgid and all payload variables
135135
*/
136-
public msg_available_modes( long custom_mode, short number_modes, short mode_index, short standard_mode, short base_mode, byte[] mode_name) {
136+
public msg_available_modes( long custom_mode, long properties, short number_modes, short mode_index, short standard_mode, byte[] mode_name) {
137137
this.msgid = MAVLINK_MSG_ID_AVAILABLE_MODES;
138138

139139
this.custom_mode = custom_mode;
140+
this.properties = properties;
140141
this.number_modes = number_modes;
141142
this.mode_index = mode_index;
142143
this.standard_mode = standard_mode;
143-
this.base_mode = base_mode;
144144
this.mode_name = mode_name;
145145

146146
}
147147

148148
/**
149149
* Constructor for a new message, initializes everything
150150
*/
151-
public msg_available_modes( long custom_mode, short number_modes, short mode_index, short standard_mode, short base_mode, byte[] mode_name, int sysid, int compid, boolean isMavlink2) {
151+
public msg_available_modes( long custom_mode, long properties, short number_modes, short mode_index, short standard_mode, byte[] mode_name, int sysid, int compid, boolean isMavlink2) {
152152
this.msgid = MAVLINK_MSG_ID_AVAILABLE_MODES;
153153
this.sysid = sysid;
154154
this.compid = compid;
155155
this.isMavlink2 = isMavlink2;
156156

157157
this.custom_mode = custom_mode;
158+
this.properties = properties;
158159
this.number_modes = number_modes;
159160
this.mode_index = mode_index;
160161
this.standard_mode = standard_mode;
161-
this.base_mode = base_mode;
162162
this.mode_name = mode_name;
163163

164164
}
@@ -182,12 +182,12 @@ public msg_available_modes(MAVLinkPacket mavLinkPacket) {
182182
* Sets the buffer of this message with a string, adds the necessary padding
183183
*/
184184
public void setMode_Name(String str) {
185-
int len = Math.min(str.length(), 50);
185+
int len = Math.min(str.length(), 35);
186186
for (int i=0; i<len; i++) {
187187
mode_name[i] = (byte) str.charAt(i);
188188
}
189189

190-
for (int i=len; i<50; i++) { // padding for the rest of the buffer
190+
for (int i=len; i<35; i++) { // padding for the rest of the buffer
191191
mode_name[i] = 0;
192192
}
193193
}
@@ -197,7 +197,7 @@ public void setMode_Name(String str) {
197197
*/
198198
public String getMode_Name() {
199199
StringBuffer buf = new StringBuffer();
200-
for (int i = 0; i < 50; i++) {
200+
for (int i = 0; i < 35; i++) {
201201
if (mode_name[i] != 0)
202202
buf.append((char) mode_name[i]);
203203
else
@@ -212,7 +212,7 @@ public String getMode_Name() {
212212
*/
213213
@Override
214214
public String toString() {
215-
return "MAVLINK_MSG_ID_AVAILABLE_MODES - sysid:"+sysid+" compid:"+compid+" custom_mode:"+custom_mode+" number_modes:"+number_modes+" mode_index:"+mode_index+" standard_mode:"+standard_mode+" base_mode:"+base_mode+" mode_name:"+mode_name+"";
215+
return "MAVLINK_MSG_ID_AVAILABLE_MODES - sysid:"+sysid+" compid:"+compid+" custom_mode:"+custom_mode+" properties:"+properties+" number_modes:"+number_modes+" mode_index:"+mode_index+" standard_mode:"+standard_mode+" mode_name:"+mode_name+"";
216216
}
217217

218218
/**

development/msg_current_mode.java

+14-14
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ This should be emitted on any mode change, and broadcast at low rate (nominally
2121
public class msg_current_mode extends MAVLinkMessage {
2222

2323
public static final int MAVLINK_MSG_ID_CURRENT_MODE = 436;
24-
public static final int MAVLINK_MSG_LENGTH = 6;
24+
public static final int MAVLINK_MSG_LENGTH = 9;
2525
private static final long serialVersionUID = MAVLINK_MSG_ID_CURRENT_MODE;
2626

2727

@@ -33,18 +33,18 @@ public class msg_current_mode extends MAVLinkMessage {
3333
public long custom_mode;
3434

3535
/**
36-
* Standard mode.
36+
* The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied
3737
*/
38-
@Description("Standard mode.")
38+
@Description("The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied")
3939
@Units("")
40-
public short standard_mode;
40+
public long intended_custom_mode;
4141

4242
/**
43-
* System mode bitmap.
43+
* Standard mode.
4444
*/
45-
@Description("System mode bitmap.")
45+
@Description("Standard mode.")
4646
@Units("")
47-
public short base_mode;
47+
public short standard_mode;
4848

4949

5050
/**
@@ -59,8 +59,8 @@ public MAVLinkPacket pack() {
5959
packet.msgid = MAVLINK_MSG_ID_CURRENT_MODE;
6060

6161
packet.payload.putUnsignedInt(custom_mode);
62+
packet.payload.putUnsignedInt(intended_custom_mode);
6263
packet.payload.putUnsignedByte(standard_mode);
63-
packet.payload.putUnsignedByte(base_mode);
6464

6565
if (isMavlink2) {
6666

@@ -78,8 +78,8 @@ public void unpack(MAVLinkPayload payload) {
7878
payload.resetIndex();
7979

8080
this.custom_mode = payload.getUnsignedInt();
81+
this.intended_custom_mode = payload.getUnsignedInt();
8182
this.standard_mode = payload.getUnsignedByte();
82-
this.base_mode = payload.getUnsignedByte();
8383

8484
if (isMavlink2) {
8585

@@ -96,27 +96,27 @@ public msg_current_mode() {
9696
/**
9797
* Constructor for a new message, initializes msgid and all payload variables
9898
*/
99-
public msg_current_mode( long custom_mode, short standard_mode, short base_mode) {
99+
public msg_current_mode( long custom_mode, long intended_custom_mode, short standard_mode) {
100100
this.msgid = MAVLINK_MSG_ID_CURRENT_MODE;
101101

102102
this.custom_mode = custom_mode;
103+
this.intended_custom_mode = intended_custom_mode;
103104
this.standard_mode = standard_mode;
104-
this.base_mode = base_mode;
105105

106106
}
107107

108108
/**
109109
* Constructor for a new message, initializes everything
110110
*/
111-
public msg_current_mode( long custom_mode, short standard_mode, short base_mode, int sysid, int compid, boolean isMavlink2) {
111+
public msg_current_mode( long custom_mode, long intended_custom_mode, short standard_mode, int sysid, int compid, boolean isMavlink2) {
112112
this.msgid = MAVLINK_MSG_ID_CURRENT_MODE;
113113
this.sysid = sysid;
114114
this.compid = compid;
115115
this.isMavlink2 = isMavlink2;
116116

117117
this.custom_mode = custom_mode;
118+
this.intended_custom_mode = intended_custom_mode;
118119
this.standard_mode = standard_mode;
119-
this.base_mode = base_mode;
120120

121121
}
122122

@@ -140,7 +140,7 @@ public msg_current_mode(MAVLinkPacket mavLinkPacket) {
140140
*/
141141
@Override
142142
public String toString() {
143-
return "MAVLINK_MSG_ID_CURRENT_MODE - sysid:"+sysid+" compid:"+compid+" custom_mode:"+custom_mode+" standard_mode:"+standard_mode+" base_mode:"+base_mode+"";
143+
return "MAVLINK_MSG_ID_CURRENT_MODE - sysid:"+sysid+" compid:"+compid+" custom_mode:"+custom_mode+" intended_custom_mode:"+intended_custom_mode+" standard_mode:"+standard_mode+"";
144144
}
145145

146146
/**

0 commit comments

Comments
 (0)