Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/add metadata to Java MAVLink message class fields #694

32 changes: 32 additions & 0 deletions generator/java/lib/Messages/Description.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
package com.MAVLink.Messages;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;
import java.lang.reflect.Field;

@Documented
@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
@SuppressWarnings("unchecked")
/**
* Description annotation to provide programmatic access to the MAVLink description for each field
*/
public @interface Description {

String value();

class Test {

@Description("The speed of the drone")
public float speed;

public static void main(String[] args) throws Exception {
Field f = Test.class.getField("speed");
Description anno = (Description) f.getAnnotation(Description.class);
System.out.println(anno.value());
}
}
}
42 changes: 42 additions & 0 deletions generator/java/lib/Messages/Units.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package com.MAVLink.Messages;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;
import java.lang.reflect.Field;

@Documented
@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
@SuppressWarnings("unchecked")
/**
* Units annotation to provide programmatic access to the MAVLink units for a given field.
*
* The standard list of units can be found in the MAVLink Schema.
*
* @see <a href="https://github.com/ArduPilot/pymavlink/blob/master/generator/mavschema.xsd#L81">MAVLink Schema</a>
*
* A snapshot of the allowable units is available in the UnitsEnum class to prevent typos
* @see {@link com.MAVLink.Messages.UnitsEnum}
*
*/
public @interface Units {
/**
* The string value of the units. A string was used to prevent brittleness as the list of valid units change
* @return
*/
String value();

class Test {
@Units("m/s")
public float speed;

public static void main(String[] args) throws Exception {
Field field = Test.class.getField("speed");
Units annotation = (Units) field.getAnnotation(Units.class);
System.out.println(UnitsEnum.fromName(annotation.value()));
}
}
}
127 changes: 127 additions & 0 deletions generator/java/lib/Messages/UnitsEnum.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
package com.MAVLink.Messages;

import java.util.HashMap;
import java.util.Map;

/**
* Units enumeration to be used to prevent typos.
*
* This enumerated list is a snapshot of the the standard list of units found in the MAVLink Schema.
*
* @see <a href="https://github.com/ArduPilot/pymavlink/blob/master/generator/mavschema.xsd#L81">MAVLink Schema</a>
*
*/
public enum UnitsEnum {
// time
S("s"), // seconds
DS("ds"),// deciseconds
CS("cs"),// centiseconds
MS("ms"),// milliseconds
US("us"),// microseconds
HZ("Hz"),// Herz
MHZ("MHz"),// Mega-Herz
// distance
KM("km"),// kilometres
DAM("dam"),// decametres
M("m"),// metres
M_PER_SEC("m/s"),// metres per second
M_PER_SEC_SEC("m/s/s"),// metres per second per second
M_PER_SEC_5("m/s*5"),// metres per second * 5 required from dagar for HIGH_LATENCY2 message
DM("dm"),// decimetres
DM_PER_S("dm/s"),// decimetres per second
CM("cm"),// centimetres
CM2("cm^2"),// centimetres squared (typically used in variance)
CM_PER_S("cm/s"),// centimetres per second
MM("mm"),// millimetres
MM_PER_S("mm/s"),// millimetres per second
MM_PER_H("mm/h"),// millimetres per hour
//temperature
K("K"),// Kelvin
DEG_C("degC"),// degrees Celsius
CDEG_C("cdegC"),// centi degrees Celsius
//angle
RAD("rad"),// radians
RAD_PER_S("rad/s"),// radians per second
MRAD_PER_S("mrad/s"),// milli-radians per second
DEG("deg"),// degrees
DEG_OVER_2("deg/2"),// degrees/2 required from dagar for HIGH_LATENCY2 message
DEG_PER_S("deg/s"),// degrees per second
CDEG("cdeg"),// centidegrees
CDEG_PER_S("cdeg/s"),// centidegrees per second
DEGe5("degE5"),// degrees * 10E5
DEGE7("degE7"),// degrees * 10E7
RPM("rpm"),// rotations per minute
//electricity
V("V"),// Volt
CV("cV"),// centi-Volt
MV("mV"),// milli-Volt
A("A"),// Ampere
CA("cA"),// centi-Ampere
MA("mA"),// milli-Ampere
MAH("mAh"),// milli-Ampere hour
//magnetism
MT("mT"),// milli-Tesla
GAUSS("gauss"),// Gauss
MGAUSS("mgauss"),// milli-Gauss
// energy
HJ("hJ"),// hecto-Joule
//power
W("W"),// Watt
//force
MG("mG"),// milli-G
//mass
G("g"),// grams
KG("kg"),// kilograms
//pressure
PA("Pa"),// Pascal
HPA("hPa"),// hecto-Pascal
KPA("kPa"),// kilo-Pascal
MBAR("mbar"),// millibar
//ratio
PERCENT("%"),// percent
DPERCENT("d%"),// decipercent
CPERCENT("c%"),// centipercent
DB("dB"),// Deci-Bell
DBM("dBm"),// Deci-Bell-milliwatts
//digital
KIB("KiB"),// Kibibyte (1024 bytes)
KIB_PER_S("KiB/s"),// Kibibyte (1024 bytes) per second
MIB("MiB"),// Mebibyte (1024*1024 bytes)
MIB_PER_S("MiB/s"),// Mebibyte (1024*1024 bytes) per second
BYTES("bytes"),// bytes
BYTES_PER_S("bytes/s"),// bytes per second
BITS_PER_S("bits/s"),// bits per second
PIX("pix"),// pixels
DPIX("dpix"),// decipixels
//flow
G_PER_MIN("g/min"),// grams/minute
CM3_PER_MIN("cm^3/min"),// cubic centimetres/minute
//volume
CM3("cm^3"),// cubic centimetres
L("l");// liters
private final String name;
private static final Map<String, UnitsEnum> toEnum = new HashMap<>();

static {
for (UnitsEnum ue : UnitsEnum.values()) {
toEnum.put(ue.getName(), ue);
}
}

UnitsEnum(String name) {
this.name = name;
}

public String getName() {
return name;
}

@Override
public String toString() {
return this.name;
}

public static UnitsEnum fromName(String name) {
return toEnum.get(name);
}
}
22 changes: 19 additions & 3 deletions generator/mavgen_java.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ def generate_enums(basename, xml):
* ${description}
*/
public class ${name} {
${{entry: public static final long ${name} = ${value}L; /* ${description} |${{param:${description}| }} */
${{entry: public static final int ${name} = ${value}; /* ${description} |${{param:${description}| }} */
}}
}
''', en)
Expand Down Expand Up @@ -151,6 +151,8 @@ def generate_message_h(directory, m):
import com.MAVLink.MAVLinkPacket;
import com.MAVLink.Messages.MAVLinkMessage;
import com.MAVLink.Messages.MAVLinkPayload;
import com.MAVLink.Messages.Units;
import com.MAVLink.Messages.Description;

/**
* ${description}
Expand All @@ -165,6 +167,8 @@ def generate_message_h(directory, m):
/**
* ${description}
*/
@Description("${description}")
@Units("${units}")
public ${type} ${name}${array_suffix};
}}

Expand Down Expand Up @@ -573,7 +577,8 @@ def generate_MAVLinkMessage(directory, xml_list):
def copy_fixed_headers(directory, xml):
'''copy the fixed protocol headers to the target directory'''
import shutil
hlist = [ 'Parser.java', 'Messages/MAVLinkMessage.java', 'Messages/MAVLinkPayload.java', 'Messages/MAVLinkStats.java' ]
hlist = [ 'Parser.java', 'Messages/MAVLinkMessage.java', 'Messages/MAVLinkPayload.java', 'Messages/MAVLinkStats.java',
'Messages/Description.java', 'Messages/Units.java', 'Messages/UnitsEnum.java']
basepath = os.path.dirname(os.path.realpath(__file__))
srcpath = os.path.join(basepath, 'java/lib')
print("Copying fixed headers")
Expand Down Expand Up @@ -777,10 +782,14 @@ def generate_one(basename, xml):
else:
f.putname = f.const_value

# fix types to java
for m in xml.message:
for f in m.ordered_fields:
# fix types to java
f.type = mavfmt(f)
# remove brackets in units
f.units = removeBrackets(f.units)
# Escape quotes in description
f.description = cleanText(f.description);

# separate base fields from MAVLink 2 extended fields
for m in xml.message:
Expand All @@ -794,6 +803,13 @@ def generate_one(basename, xml):
for m in xml.message:
generate_message_h(directory, m)

def removeBrackets(text):
return text.replace("[","").replace("]","")

def cleanText(text):
text = text.replace("\n"," ")
text = text.replace("\r"," ")
return text.replace("\"","'")

def generate(basename, xml_list):
'''generate complete MAVLink Java implemenation'''
Expand Down
9 changes: 1 addition & 8 deletions generator/mavgen_wlua.py
Original file line number Diff line number Diff line change
Expand Up @@ -313,14 +313,7 @@ def generate_field_dissector(outf, msg, field, offset, cmd=None, param=None):
t.write(outf,
"""
field_offset = offset + ${foffset}
value = padded(field_offset, ${fbytes}):${ftvbfunc}()
if (field_offset + ${fbytes} <= limit) then
subtree = tree:add_le(f.${fvar}, buffer(field_offset, ${fbytes}), value)
elseif (field_offset < limit) then
subtree = tree:add_le(f.${fvar}, buffer(field_offset, limit - offset - ${foffset}), value)
else
subtree = tree:add_le(f.${fvar}, value)
end
subtree, value = tree:add_le(f.${fvar}, padded(field_offset, ${fbytes}))
""", {'foffset': offset + i * size, 'fbytes': size, 'ftvbfunc': tvb_func, 'fvar': field_var})

if flag_enum is not None:
Expand Down