Merge remote-tracking branch 'px4/beta' into beta_mavlink

This commit is contained in:
Julian Oes 2014-02-16 12:37:15 +01:00
commit 875ba3bb2b
19 changed files with 802 additions and 195 deletions

View File

@ -1,3 +1,4 @@
parameters.wiki
parameters.xml
parameters.wikirpc.xml
cookies.txt

View File

@ -1,62 +0,0 @@
import output
from xml.sax.saxutils import escape
class DokuWikiOutput(output.Output):
def Generate(self, groups):
pre_text = """<?xml version='1.0'?>
<methodCall>
<methodName>wiki.putPage</methodName>
<params>
<param>
<value>
<string>:firmware:parameters</string>
</value>
</param>
<param>
<value>
<string>"""
result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values."
for group in groups:
result += "==== %s ====\n\n" % group.GetName()
result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n"
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
for param in group.GetParams():
code = param.GetFieldValue("code")
name = param.GetFieldValue("short_desc")
name = name.replace("\n", "")
result += "| %s | %s " % (code, name)
min_val = param.GetFieldValue("min")
if min_val is not None:
result += " | %s " % min_val
else:
result += " | "
max_val = param.GetFieldValue("max")
if max_val is not None:
result += " | %s " % max_val
else:
result += " | "
def_val = param.GetFieldValue("default")
if def_val is not None:
result += "| %s " % def_val
else:
result += " | "
long_desc = param.GetFieldValue("long_desc")
if long_desc is not None:
long_desc = long_desc.replace("\n", "")
result += "| %s " % long_desc
else:
result += " | "
result += " |\n"
result += "\n"
post_text = """</string>
</value>
</param>
<param>
<value>
<name>sum</name>
<string>Updated parameters automagically from code.</string>
</value>
</param>
</params>
</methodCall>"""
return pre_text + escape(result) + post_text

View File

@ -1,5 +0,0 @@
class Output(object):
def Save(self, groups, fn):
data = self.Generate(groups)
with open(fn, 'w') as f:
f.write(data)

View File

@ -1,7 +1,7 @@
import output
import codecs
class DokuWikiOutput(output.Output):
def Generate(self, groups):
class DokuWikiListingsOutput():
def __init__(self, groups):
result = ""
for group in groups:
result += "==== %s ====\n\n" % group.GetName()
@ -24,4 +24,8 @@ class DokuWikiOutput(output.Output):
if def_val is not None:
result += "* Default value: %s\n" % def_val
result += "\n"
return result
self.output = result
def Save(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
f.write(self.output)

View File

@ -0,0 +1,76 @@
from xml.sax.saxutils import escape
import codecs
class DokuWikiTablesOutput():
def __init__(self, groups):
result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values.\n\n"
for group in groups:
result += "==== %s ====\n\n" % group.GetName()
result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n"
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
for param in group.GetParams():
code = param.GetFieldValue("code")
name = param.GetFieldValue("short_desc")
min_val = param.GetFieldValue("min")
max_val = param.GetFieldValue("max")
def_val = param.GetFieldValue("default")
long_desc = param.GetFieldValue("long_desc")
name = name.replace("\n", " ")
result += "| %s | %s |" % (code, name)
if min_val is not None:
result += " %s |" % min_val
else:
result += " |"
if max_val is not None:
result += " %s |" % max_val
else:
result += " |"
if def_val is not None:
result += " %s |" % def_val
else:
result += " |"
if long_desc is not None:
long_desc = long_desc.replace("\n", " ")
result += " %s |" % long_desc
else:
result += " |"
result += "\n"
result += "\n"
self.output = result;
def Save(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
f.write(self.output)
def SaveRpc(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
f.write("""<?xml version='1.0'?>
<methodCall>
<methodName>wiki.putPage</methodName>
<params>
<param>
<value>
<string>:firmware:parameters</string>
</value>
</param>
<param>
<value>
<string>""")
f.write(escape(self.output))
f.write("""</string>
</value>
</param>
<param>
<value>
<name>sum</name>
<string>Updated parameters automagically from code.</string>
</value>
</param>
</params>
</methodCall>""")

View File

@ -1,8 +1,8 @@
import output
from xml.dom.minidom import getDOMImplementation
import codecs
class XMLOutput(output.Output):
def Generate(self, groups):
class XMLOutput():
def __init__(self, groups):
impl = getDOMImplementation()
xml_document = impl.createDocument(None, "parameters", None)
xml_parameters = xml_document.documentElement
@ -19,4 +19,8 @@ class XMLOutput(output.Output):
xml_param.appendChild(xml_field)
xml_value = xml_document.createTextNode(value)
xml_field.appendChild(xml_value)
return xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8")
self.xml_document = xml_document
def Save(self, filename):
with codecs.open(filename, 'w', 'utf-8') as f:
self.xml_document.writexml(f, indent=" ", addindent=" ", newl="\n")

View File

@ -40,22 +40,28 @@
#
import scanner
import parser
import xmlout
import dokuwikiout
import srcparser
import output_xml
import output_dokuwiki_tables
import output_dokuwiki_listings
# Initialize parser
prs = parser.Parser()
prs = srcparser.Parser()
# Scan directories, and parse the files
sc = scanner.Scanner()
sc.ScanDir("../../src", prs)
output = prs.GetParamGroups()
groups = prs.GetParamGroups()
# Output into XML
out = xmlout.XMLOutput()
out.Save(output, "parameters.xml")
out = output_xml.XMLOutput(groups)
out.Save("parameters.xml")
# Output into DokuWiki
out = dokuwikiout.DokuWikiOutput()
out.Save(output, "parameters.wiki")
# Output to DokuWiki listings
#out = output_dokuwiki_listings.DokuWikiListingsOutput(groups)
#out.Save("parameters.wiki")
# Output to DokuWiki tables
out = output_dokuwiki_tables.DokuWikiTablesOutput(groups)
out.Save("parameters.wiki")
out.SaveRpc("parameters.wikirpc.xml")

View File

@ -1,5 +1,6 @@
import os
import re
import codecs
class Scanner(object):
"""
@ -29,6 +30,6 @@ class Scanner(object):
Scans provided file and passes its contents to the parser using
parser.Parse method.
"""
with open(path, 'r') as f:
with codecs.open(path, 'r', 'utf-8') as f:
contents = f.read()
parser.Parse(contents)

View File

@ -28,8 +28,7 @@ class ParameterGroup(object):
state of the parser.
"""
return sorted(self.params,
cmp=lambda x, y: cmp(x.GetFieldValue("code"),
y.GetFieldValue("code")))
key=lambda x: x.GetFieldValue("code"))
class Parameter(object):
"""
@ -61,9 +60,10 @@ class Parameter(object):
"""
Return list of existing field codes in convenient order
"""
return sorted(self.fields.keys(),
cmp=lambda x, y: cmp(self.priority.get(y, 0),
self.priority.get(x, 0)) or cmp(x, y))
keys = self.fields.keys()
keys = sorted(keys)
keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True)
return keys
def GetFieldValue(self, code):
"""
@ -197,7 +197,7 @@ class Parser(object):
if tag == "group":
group = tags[tag]
elif tag not in self.valid_tags:
sys.stderr.write("Skipping invalid"
sys.stderr.write("Skipping invalid "
"documentation tag: '%s'\n" % tag)
else:
param.SetField(tag, tags[tag])
@ -214,7 +214,7 @@ class Parser(object):
object. Note that returned object is not a copy. Modifications affect
state of the parser.
"""
return sorted(self.param_groups.values(),
cmp=lambda x, y: cmp(self.priority.get(y.GetName(), 0),
self.priority.get(x.GetName(), 0)) or cmp(x.GetName(),
y.GetName()))
groups = self.param_groups.values()
groups = sorted(groups, key=lambda x: x.GetName())
groups = sorted(groups, key=lambda x: self.priority.get(x.GetName(), 0), reverse=True)
return groups

View File

@ -2,4 +2,4 @@ python px_process_params.py
rm cookies.txt
curl --cookie cookies.txt --cookie-jar cookies.txt --user-agent Mozilla/4.0 --data "u=$XMLRPCUSER&p=$XMLRPCPASS" https://pixhawk.org/start?do=login
curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wiki "https://pixhawk.org/lib/exe/xmlrpc.php"
curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wikirpc.xml "https://pixhawk.org/lib/exe/xmlrpc.php"

View File

@ -50,6 +50,7 @@
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
*/
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@ -388,7 +389,7 @@ test()
err(1, "immediate read failed");
warnx("single read");
warnx("diff pressure: %d pa", (double)report.differential_pressure_pa);
warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
@ -413,7 +414,7 @@ test()
err(1, "periodic read failed");
warnx("periodic read %u", i);
warnx("diff pressure: %d pa", report.differential_pressure_pa);
warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}

View File

@ -45,28 +45,46 @@
#include <systemlib/param/param.h>
/*
* Launch detection parameters, accessible via MAVLink
* Catapult launch detection parameters, accessible via MAVLink
*
*/
/* Catapult Launch detection */
// @DisplayName Switch to enable launchdetection
// @Description if set to 1 launchdetection is enabled
// @Range 0 or 1
/**
* Enable launch detection.
*
* @min 0
* @max 1
* @group Launch detection
*/
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
// @DisplayName Catapult Accelerometer Threshold
// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
// @Range > 0
/**
* Catapult accelerometer theshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
* @min 0
* @group Launch detection
*/
PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
// @DisplayName Catapult Time Threshold
// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
// @Range > 0, in seconds
/**
* Catapult time theshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
* @min 0
* @group Launch detection
*/
PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
// @DisplayName Throttle setting while detecting the launch
// @Description The throttle is set to this value while the system is waiting for the takeoff
// @Range 0 to 1
/**
* Throttle setting while detecting launch.
*
* The throttle is set to this value while the system is waiting for the take-off.
*
* @min 0
* @max 1
* @group Launch detection
*/
PARAM_DEFINE_FLOAT(LAUN_THR_PRE, 0.0f);

View File

@ -48,7 +48,39 @@
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
/**
* Empty cell voltage.
*
* Defines the voltage where a single cell of the battery is considered empty.
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f);
/**
* Full cell voltage.
*
* Defines the voltage where a single cell of the battery is considered full.
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f);
/**
* Number of cells.
*
* Defines the number of cells the attached battery consists of.
*
* @group Battery Calibration
*/
PARAM_DEFINE_INT32(BAT_N_CELLS, 3);
/**
* Battery capacity.
*
* Defines the capacity of the attached battery.
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);

View File

@ -40,12 +40,10 @@
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
/*
* Controller parameters, accessible via MAVLink
*
*/
/**
@ -119,58 +117,268 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
*/
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
/**
* Controller roll limit
*
* The maximum roll the controller will output.
*
* @unit degrees
* @min 0.0
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f);
PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Throttle limit max
*
* This is the maximum throttle % that can be used by the controller.
* For overpowered aircraft, this should be reduced to a value that
* provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
/**
* Throttle limit min
*
* This is the minimum throttle % that can be used by the controller.
* For electric aircraft this will normally be set to zero, but can be set
* to a small non-zero value if a folding prop is fitted to prevent the
* prop from folding and unfolding repeatedly in-flight or to provide
* some aerodynamic drag from a turning prop to improve the descent rate.
*
* For aircraft with internal combustion engine this parameter should be set
* for desired idle rpm.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Throttle limit value before flare
*
* This throttle value will be set as throttle limit at FW_LND_TLALT,
* before arcraft will flare.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
/**
* Maximum climb rate
*
* This is the best climb rate that the aircraft can achieve with
* the throttle set to THR_MAX and the airspeed set to the
* default value. For electric aircraft make sure this number can be
* achieved towards the end of flight when the battery voltage has reduced.
* The setting of this parameter can be checked by commanding a positive
* altitude change of 100m in loiter, RTL or guided mode. If the throttle
* required to climb is close to THR_MAX and the aircraft is maintaining
* airspeed, then this parameter is set correctly. If the airspeed starts
* to reduce, then the parameter is set to high, and if the throttle
* demand required to climb and maintain speed is noticeably less than
* FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
* FW_THR_MAX reduced.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
/**
* Minimum descent rate
*
* This is the sink rate of the aircraft with the throttle
* set to THR_MIN and flown at the same airspeed as used
* to measure FW_T_CLMB_MAX.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
/**
* Maximum descent rate
*
* This sets the maximum descent rate that the controller will use.
* If this value is too large, the aircraft can over-speed on descent.
* This should be set to a value that can be achieved without
* exceeding the lower pitch angle limit and without over-speeding
* the aircraft.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
/**
* TECS time constant
*
* This is the time constant of the TECS control algorithm (in seconds).
* Smaller values make it faster to respond, larger values make it slower
* to respond.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
/**
* Throttle damping factor
*
* This is the damping gain for the throttle demand loop.
* Increase to add damping to correct for oscillations in speed and height.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
/**
* Integrator gain
*
* This is the integrator gain on the control loop.
* Increasing this gain increases the speed at which speed
* and height offsets are trimmed out, but reduces damping and
* increases overshoot.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
/**
* Maximum vertical acceleration
*
* This is the maximum vertical acceleration (in metres/second^2)
* either up or down that the controller will use to correct speed
* or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
* allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
/**
* Complementary filter "omega" parameter for height
*
* This is the cross-over frequency (in radians/second) of the complementary
* filter used to fuse vertical acceleration and barometric height to obtain
* an estimate of height rate and height. Increasing this frequency weights
* the solution more towards use of the barometer, whilst reducing it weights
* the solution more towards use of the accelerometer data.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
/**
* Complementary filter "omega" parameter for speed
*
* This is the cross-over frequency (in radians/second) of the complementary
* filter used to fuse longitudinal acceleration and airspeed to obtain an
* improved airspeed estimate. Increasing this frequency weights the solution
* more towards use of the arispeed sensor, whilst reducing it weights the
* solution more towards use of the accelerometer data.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
/**
* Roll -> Throttle feedforward
*
* Increasing this gain turn increases the amount of throttle that will
* be used to compensate for the additional drag created by turning.
* Ideally this should be set to approximately 10 x the extra sink rate
* in m/s created by a 45 degree bank turn. Increase this gain if
* the aircraft initially loses energy in turns and reduce if the
* aircraft initially gains energy in turns. Efficient high aspect-ratio
* aircraft (eg powered sailplanes) can use a lower value, whereas
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
/**
* Speed <--> Altitude priority
*
* This parameter adjusts the amount of weighting that the pitch control
* applies to speed vs height errors. Setting it to 0.0 will cause the
* pitch control to control height and ignore speed errors. This will
* normally improve height accuracy but give larger airspeed errors.
* Setting it to 2.0 will cause the pitch control loop to control speed
* and ignore height errors. This will normally reduce airspeed errors,
* but give larger height errors. The default value of 1.0 allows the pitch
* control to simultaneously control height and speed.
* Note to Glider Pilots - set this parameter to 2.0 (The glider will
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
/**
* Pitch damping factor
*
* This is the damping gain for the pitch demand loop. Increase to add
* damping to correct for oscillations in height. The default value of 0.0
* will work well provided the pitch to servo controller has been tuned
* properly.
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
/**
* Height rate P factor
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
/**
* Speed rate P factor
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
/**
* Landing slope angle
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
/**
* Landing slope length
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f);
/**
*
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
/**
* Landing flare altitude (relative)
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f);
/**
* Landing throttle limit altitude (relative)
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f);
/**
* Landing heading hold horizontal distance
*
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);

View File

@ -72,8 +72,20 @@
// #include <uORB/topics/mission_result.h>
/* define MAVLink specific parameters */
/**
* MAVLink system ID
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
/**
* MAVLink component ID
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
/**
* MAVLink type
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
mavlink_system_t mavlink_system = {

View File

@ -45,11 +45,17 @@
#include <systemlib/param/param.h>
/*
* geofence parameters, accessible via MAVLink
*
* Geofence parameters, accessible via MAVLink
*/
// @DisplayName Switch to enable geofence
// @Description if set to 1 geofence is enabled, defaults to 1 because geofence is only enabled when the geofence.txt file is present
// @Range 0 or 1
/**
* Enable geofence.
*
* Set to 1 to enable geofence.
* Defaults to 1 because geofence is only enabled when the geofence.txt file is present.
*
* @min 0
* @max 1
* @group Geofence
*/
PARAM_DEFINE_INT32(GF_ON, 1);

View File

@ -50,15 +50,72 @@
/*
* Navigator parameters, accessible via MAVLink
*
*/
/**
* Minimum altitude
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
/**
* Waypoint acceptance radius.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
/**
* Loiter radius.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
/**
* @group Navigation
*/
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
/**
* Default take-off altitude.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
/**
* Landing altitude.
*
* Slowly descend from this altitude when landing.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
/**
* Return-to-land altitude.
*
* Minimum altitude for going home in RTL mode.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); // delay after descend before landing, if set to -1 the system will not land but loiter at NAV_LAND_ALT
PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0); // enable parachute deployment
/**
* Return-to-land delay.
*
* Delay after descend before landing.
* If set to -1 the system will not land but loiter at NAV_LAND_ALT.
*
* @group Navigation
*/
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f);
/**
* Enable parachute deployment.
*
* @group Navigation
*/
PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0);

View File

@ -42,13 +42,10 @@
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
/**
* Gyro X offset
*
* This is an X-axis offset for the gyro. Adjust it according to the calibration data.
* Gyro X-axis offset
*
* @min -10.0
* @max 10.0
@ -57,7 +54,7 @@
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
/**
* Gyro Y offset
* Gyro Y-axis offset
*
* @min -10.0
* @max 10.0
@ -66,7 +63,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
/**
* Gyro Z offset
* Gyro Z-axis offset
*
* @min -5.0
* @max 5.0
@ -75,9 +72,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
/**
* Gyro X scaling
*
* X-axis scaling.
* Gyro X-axis scaling factor
*
* @min -1.5
* @max 1.5
@ -86,9 +81,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
/**
* Gyro Y scaling
*
* Y-axis scaling.
* Gyro Y-axis scaling factor
*
* @min -1.5
* @max 1.5
@ -97,9 +90,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
/**
* Gyro Z scaling
*
* Z-axis scaling.
* Gyro Z-axis scaling factor
*
* @min -1.5
* @max 1.5
@ -107,10 +98,9 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
*/
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
/**
* Magnetometer X offset
*
* This is an X-axis offset for the magnetometer.
* Magnetometer X-axis offset
*
* @min -500.0
* @max 500.0
@ -119,9 +109,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
/**
* Magnetometer Y offset
*
* This is an Y-axis offset for the magnetometer.
* Magnetometer Y-axis offset
*
* @min -500.0
* @max 500.0
@ -130,9 +118,7 @@ PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
/**
* Magnetometer Z offset
*
* This is an Z-axis offset for the magnetometer.
* Magnetometer Z-axis offset
*
* @min -500.0
* @max 500.0
@ -140,24 +126,134 @@ PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
*/
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
/**
* Magnetometer X-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
/**
* Magnetometer Y-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_MAG_YSCALE, 1.0f);
/**
* Magnetometer Z-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_MAG_ZSCALE, 1.0f);
/**
* Accelerometer X-axis offset
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_XOFF, 0.0f);
/**
* Accelerometer Y-axis offset
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_YOFF, 0.0f);
/**
* Accelerometer Z-axis offset
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_ZOFF, 0.0f);
/**
* Accelerometer X-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
/**
* Accelerometer Y-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
/**
* Accelerometer Z-axis scaling factor
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
/**
* Differential pressure sensor offset
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
/**
* Differential pressure sensor analog enabled
*
* @group Sensor Calibration
*/
PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
/**
* Board rotation
*
* This parameter defines the rotation of the FMU board relative to the platform.
* Possible values are:
* 0 = No rotation
* 1 = Yaw 45°
* 2 = Yaw 90°
* 3 = Yaw 135°
* 4 = Yaw 180°
* 5 = Yaw 225°
* 6 = Yaw 270°
* 7 = Yaw 315°
* 8 = Roll 180°
* 9 = Roll 180°, Yaw 45°
* 10 = Roll 180°, Yaw 90°
* 11 = Roll 180°, Yaw 135°
* 12 = Pitch 180°
* 13 = Roll 180°, Yaw 225°
* 14 = Roll 180°, Yaw 270°
* 15 = Roll 180°, Yaw 315°
* 16 = Roll 90°
* 17 = Roll 90°, Yaw 45°
* 18 = Roll 90°, Yaw 90°
* 19 = Roll 90°, Yaw 135°
* 20 = Roll 270°
* 21 = Roll 270°, Yaw 45°
* 22 = Roll 270°, Yaw 90°
* 23 = Roll 270°, Yaw 135°
* 24 = Pitch 90°
* 25 = Pitch 270°
*
* @group Sensor Calibration
*/
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
/**
* External magnetometer rotation
*
* This parameter defines the rotation of the external magnetometer relative
* to the platform (not relative to the FMU).
* See SENS_BOARD_ROT for possible values.
*
* @group Sensor Calibration
*/
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
/**
* RC Channel 1 Minimum
*
@ -367,20 +463,52 @@ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f);
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
#endif
PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */
/**
* DSM binding trigger.
*
* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind
*
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_DSM_BIND, -1);
/**
* Scaling factor for battery voltage sensor on PX4IO.
*
* @group Battery Calibration
*/
PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
/**
* Scaling factor for battery voltage sensor on FMU v2.
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
#else
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
/* PX4IOAR: 0.00838095238 */
/* FMU standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 */
/* FMU with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) */
/**
* Scaling factor for battery voltage sensor on FMU v1.
*
* FMUv1 standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659
* FMUv1 with PX4IO: 0.00459340659
* FMUv1 with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) = 0.00838095238
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f);
#endif
/**
* Scaling factor for battery current sensor.
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_C_SCALING, 0.0124); /* scaling for 3DR power brick */
/**
* Roll control channel mapping.
*
@ -446,22 +574,127 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 4);
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
/**
* Return switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
/**
* Assist switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
/**
* Mission switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
/**
* Flaps channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera pitch */
PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera azimuth / yaw */
/**
* Auxiliary switch 1 channel mapping.
*
* Default function: Camera pitch
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_AUX1, 0);
/**
* Auxiliary switch 2 channel mapping.
*
* Default function: Camera roll
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
/**
* Auxiliary switch 3 channel mapping.
*
* Default function: Camera azimuth / yaw
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
/**
* Roll scaling factor
*
* @group Radio Calibration
*/
PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f);
/**
* Pitch scaling factor
*
* @group Radio Calibration
*/
PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f);
/**
* Yaw scaling factor
*
* @group Radio Calibration
*/
PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f);
PARAM_DEFINE_INT32(RC_FS_CH, 0); /**< RC failsafe channel, 0 = disable */
PARAM_DEFINE_INT32(RC_FS_MODE, 0); /**< RC failsafe mode: 0 = too low means signal loss, 1 = too high means signal loss */
PARAM_DEFINE_FLOAT(RC_FS_THR, 800); /**< RC failsafe PWM threshold */
/**
* Failsafe channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_FS_CH, 0);
/**
* Failsafe channel mode.
*
* 0 = too low means signal loss,
* 1 = too high means signal loss
*
* @min 0
* @max 1
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_FS_MODE, 0);
/**
* Failsafe channel PWM threshold.
*
* @min 0
* @max 1
* @group Radio Calibration
*/
PARAM_DEFINE_FLOAT(RC_FS_THR, 800);

View File

@ -40,8 +40,23 @@
#include <nuttx/config.h>
#include <systemlib/param/param.h>
// Auto-start script with index #n
/**
* Auto-start script index.
*
* Defines the auto-start script used to bootstrap the system.
*
* @group System
*/
PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
// Automatically configure default values
/**
* Automatically configure default values.
*
* Set to 1 to set platform-specific parameters to their default
* values on next system startup.
*
* @min 0
* @max 1
* @group System
*/
PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);