mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
Parameter documentation improvements
This commit is contained in:
@@ -5,23 +5,33 @@ class DokuWikiOutput(output.Output):
|
|||||||
result = ""
|
result = ""
|
||||||
for group in groups:
|
for group in groups:
|
||||||
result += "==== %s ====\n\n" % group.GetName()
|
result += "==== %s ====\n\n" % group.GetName()
|
||||||
|
result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
|
||||||
for param in group.GetParams():
|
for param in group.GetParams():
|
||||||
code = param.GetFieldValue("code")
|
code = param.GetFieldValue("code")
|
||||||
name = param.GetFieldValue("short_desc")
|
name = param.GetFieldValue("short_desc")
|
||||||
if code != name:
|
name = name.replace("\n", "")
|
||||||
name = "%s (%s)" % (name, code)
|
result += "| %s | %s " % (code, name)
|
||||||
result += "=== %s ===\n\n" % name
|
|
||||||
long_desc = param.GetFieldValue("long_desc")
|
|
||||||
if long_desc is not None:
|
|
||||||
result += "%s\n\n" % long_desc
|
|
||||||
min_val = param.GetFieldValue("min")
|
min_val = param.GetFieldValue("min")
|
||||||
if min_val is not None:
|
if min_val is not None:
|
||||||
result += "* Minimal value: %s\n" % min_val
|
result += "| %s " % min_val
|
||||||
|
else:
|
||||||
|
result += "|"
|
||||||
max_val = param.GetFieldValue("max")
|
max_val = param.GetFieldValue("max")
|
||||||
if max_val is not None:
|
if max_val is not None:
|
||||||
result += "* Maximal value: %s\n" % max_val
|
result += "| %s " % max_val
|
||||||
|
else:
|
||||||
|
result += "|"
|
||||||
def_val = param.GetFieldValue("default")
|
def_val = param.GetFieldValue("default")
|
||||||
if def_val is not None:
|
if def_val is not None:
|
||||||
result += "* Default value: %s\n" % def_val
|
result += "| %s " % def_val
|
||||||
result += "\n"
|
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"
|
||||||
return result
|
return result
|
||||||
|
|||||||
@@ -0,0 +1,27 @@
|
|||||||
|
import output
|
||||||
|
|
||||||
|
class DokuWikiOutput(output.Output):
|
||||||
|
def Generate(self, groups):
|
||||||
|
result = ""
|
||||||
|
for group in groups:
|
||||||
|
result += "==== %s ====\n\n" % group.GetName()
|
||||||
|
for param in group.GetParams():
|
||||||
|
code = param.GetFieldValue("code")
|
||||||
|
name = param.GetFieldValue("short_desc")
|
||||||
|
if code != name:
|
||||||
|
name = "%s (%s)" % (name, code)
|
||||||
|
result += "=== %s ===\n\n" % name
|
||||||
|
long_desc = param.GetFieldValue("long_desc")
|
||||||
|
if long_desc is not None:
|
||||||
|
result += "%s\n\n" % long_desc
|
||||||
|
min_val = param.GetFieldValue("min")
|
||||||
|
if min_val is not None:
|
||||||
|
result += "* Minimal value: %s\n" % min_val
|
||||||
|
max_val = param.GetFieldValue("max")
|
||||||
|
if max_val is not None:
|
||||||
|
result += "* Maximal value: %s\n" % max_val
|
||||||
|
def_val = param.GetFieldValue("default")
|
||||||
|
if def_val is not None:
|
||||||
|
result += "* Default value: %s\n" % def_val
|
||||||
|
result += "\n"
|
||||||
|
return result
|
||||||
@@ -1,7 +1,6 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
|
||||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -49,21 +48,75 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* L1 period
|
||||||
|
*
|
||||||
|
* This is the L1 distance and defines the tracking
|
||||||
|
* point ahead of the aircraft its following.
|
||||||
|
* A value of 25 meters works for most aircraft. Shorten
|
||||||
|
* slowly during tuning until response is sharp without oscillation.
|
||||||
|
*
|
||||||
|
* @min 1.0
|
||||||
|
* @max 100.0
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
|
PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* L1 damping
|
||||||
|
*
|
||||||
|
* Damping factor for L1 control.
|
||||||
|
*
|
||||||
|
* @min 0.6
|
||||||
|
* @max 0.9
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
|
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Default Loiter Radius
|
||||||
|
*
|
||||||
|
* This radius is used when no other loiter radius is set.
|
||||||
|
*
|
||||||
|
* @min 10.0
|
||||||
|
* @max 100.0
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
|
PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Cruise throttle
|
||||||
|
*
|
||||||
|
* This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.
|
||||||
|
*
|
||||||
|
* @min 0.0
|
||||||
|
* @max 1.0
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
|
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Negative pitch limit
|
||||||
|
*
|
||||||
|
* The minimum negative pitch the controller will output.
|
||||||
|
*
|
||||||
|
* @unit degrees
|
||||||
|
* @min -60.0
|
||||||
|
* @max 0.0
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
|
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Positive pitch limit
|
||||||
|
*
|
||||||
|
* The maximum positive pitch the controller will output.
|
||||||
|
*
|
||||||
|
* @unit degrees
|
||||||
|
* @min 0.0
|
||||||
|
* @max 60.0
|
||||||
|
* @group L1 Control
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
|
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
############################################################################
|
############################################################################
|
||||||
#
|
#
|
||||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
# Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
# modification, are permitted provided that the following conditions
|
# modification, are permitted provided that the following conditions
|
||||||
|
|||||||
@@ -1,9 +1,6 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
|
||||||
* @author Julian Oes <joes@student.ethz.ch>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -38,6 +35,10 @@
|
|||||||
* @file sensor_params.c
|
* @file sensor_params.c
|
||||||
*
|
*
|
||||||
* Parameters defined by the sensors task.
|
* Parameters defined by the sensors task.
|
||||||
|
*
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
|
* @author Julian Oes <joes@student.ethz.ch>
|
||||||
|
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <nuttx/config.h>
|
#include <nuttx/config.h>
|
||||||
@@ -45,41 +46,98 @@
|
|||||||
#include <systemlib/param/param.h>
|
#include <systemlib/param/param.h>
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Gyro X offset FIXME
|
* Gyro X offset
|
||||||
*
|
*
|
||||||
* This is an X-axis offset for the gyro.
|
* This is an X-axis offset for the gyro. Adjust it according to the calibration data.
|
||||||
* Adjust it according to the calibration data.
|
|
||||||
*
|
*
|
||||||
* @min -10.0
|
* @min -10.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group Gyro Config
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Gyro Y offset FIXME with dot.
|
* Gyro Y offset
|
||||||
*
|
*
|
||||||
* @min -10.0
|
* @min -10.0
|
||||||
* @max 10.0
|
* @max 10.0
|
||||||
* @group Gyro Config
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Gyro Z offset FIXME
|
* Gyro Z offset
|
||||||
*
|
*
|
||||||
* @min -5.0
|
* @min -5.0
|
||||||
* @max 5.0
|
* @max 5.0
|
||||||
* @group Gyro Config
|
* @group Sensor Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gyro X scaling
|
||||||
|
*
|
||||||
|
* X-axis scaling.
|
||||||
|
*
|
||||||
|
* @min -1.5
|
||||||
|
* @max 1.5
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gyro Y scaling
|
||||||
|
*
|
||||||
|
* Y-axis scaling.
|
||||||
|
*
|
||||||
|
* @min -1.5
|
||||||
|
* @max 1.5
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gyro Z scaling
|
||||||
|
*
|
||||||
|
* Z-axis scaling.
|
||||||
|
*
|
||||||
|
* @min -1.5
|
||||||
|
* @max 1.5
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
|
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Magnetometer X offset
|
||||||
|
*
|
||||||
|
* This is an X-axis offset for the magnetometer.
|
||||||
|
*
|
||||||
|
* @min -500.0
|
||||||
|
* @max 500.0
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Magnetometer Y offset
|
||||||
|
*
|
||||||
|
* This is an Y-axis offset for the magnetometer.
|
||||||
|
*
|
||||||
|
* @min -500.0
|
||||||
|
* @max 500.0
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Magnetometer Z offset
|
||||||
|
*
|
||||||
|
* This is an Z-axis offset for the magnetometer.
|
||||||
|
*
|
||||||
|
* @min -500.0
|
||||||
|
* @max 500.0
|
||||||
|
* @group Sensor Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
|
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
|
||||||
|
|
||||||
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
|
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
|
||||||
@@ -100,16 +158,114 @@ PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
|
|||||||
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
|
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
|
||||||
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
|
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 1 Minimum
|
||||||
|
*
|
||||||
|
* Minimum value for RC channel 1
|
||||||
|
*
|
||||||
|
* @min 800.0
|
||||||
|
* @max 1500.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
|
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 1 Trim
|
||||||
|
*
|
||||||
|
* Mid point value (same as min for throttle)
|
||||||
|
*
|
||||||
|
* @min 800.0
|
||||||
|
* @max 2200.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
|
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 1 Maximum
|
||||||
|
*
|
||||||
|
* Maximum value for RC channel 1
|
||||||
|
*
|
||||||
|
* @min 1500.0
|
||||||
|
* @max 2200.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
|
PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 1 Reverse
|
||||||
|
*
|
||||||
|
* Set to -1 to reverse channel.
|
||||||
|
*
|
||||||
|
* @min -1.0
|
||||||
|
* @max 1.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
|
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 1 dead zone
|
||||||
|
*
|
||||||
|
* The +- range of this value around the trim value will be considered as zero.
|
||||||
|
*
|
||||||
|
* @min 0.0
|
||||||
|
* @max 100.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f);
|
PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f);
|
||||||
|
|
||||||
PARAM_DEFINE_FLOAT(RC2_MIN, 1000);
|
/**
|
||||||
PARAM_DEFINE_FLOAT(RC2_TRIM, 1500);
|
* RC Channel 2 Minimum
|
||||||
PARAM_DEFINE_FLOAT(RC2_MAX, 2000);
|
*
|
||||||
|
* Minimum value for RC channel 2
|
||||||
|
*
|
||||||
|
* @min 800.0
|
||||||
|
* @max 1500.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_FLOAT(RC2_MIN, 1000.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 2 Trim
|
||||||
|
*
|
||||||
|
* Mid point value (same as min for throttle)
|
||||||
|
*
|
||||||
|
* @min 800.0
|
||||||
|
* @max 2200.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_FLOAT(RC2_TRIM, 1500.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 2 Maximum
|
||||||
|
*
|
||||||
|
* Maximum value for RC channel 2
|
||||||
|
*
|
||||||
|
* @min 1500.0
|
||||||
|
* @max 2200.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 2 Reverse
|
||||||
|
*
|
||||||
|
* Set to -1 to reverse channel.
|
||||||
|
*
|
||||||
|
* @min -1.0
|
||||||
|
* @max 1.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
|
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* RC Channel 2 dead zone
|
||||||
|
*
|
||||||
|
* The +- range of this value around the trim value will be considered as zero.
|
||||||
|
*
|
||||||
|
* @min 0.0
|
||||||
|
* @max 100.0
|
||||||
|
* @group Radio Calibration
|
||||||
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f);
|
PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f);
|
||||||
|
|
||||||
PARAM_DEFINE_FLOAT(RC3_MIN, 1000);
|
PARAM_DEFINE_FLOAT(RC3_MIN, 1000);
|
||||||
|
|||||||
Reference in New Issue
Block a user