mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
param_parser: cosmetic
Arduplane: doc fixes
This commit is contained in:
parent
a79f55656a
commit
3b0a4f8c68
@ -261,18 +261,18 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: FlightMode1
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
// @Description: Flight mode for switch position 2 (910 to 1230 and above 2049)
|
||||
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
|
||||
GSCALAR(flight_mode1, "FLTMODE1"),
|
||||
|
||||
// @Param: FLTMODE3
|
||||
// @DisplayName: FlightMode1
|
||||
// @Param: FLTMODE2
|
||||
// @DisplayName: FlightMode2
|
||||
// @Description: Flight mode for switch position 2 (1231 to 1360)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode2, "FLTMODE2"),
|
||||
|
||||
// @Param: FLTMODE3
|
||||
// @DisplayName: FlightMode1
|
||||
// @DisplayName: FlightMode3
|
||||
// @Description: Flight mode for switch position 3 (1361 to 1490)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
|
@ -49,7 +49,7 @@ def wiki_parameters(g, f):
|
||||
t+="|| *Value* || *Meaning* ||\n"
|
||||
for value in values:
|
||||
v = value.split(':')
|
||||
t+="|| "+v[0]+" || "+v[1]+" ||\n"
|
||||
t+="|| "+v[0]+" || "+camelcase_escape(v[1])+" ||\n"
|
||||
else:
|
||||
t += " * %s: %s\n" % (camelcase_escape(field), wikichars_escape(param.__dict__[field]))
|
||||
|
||||
@ -96,7 +96,7 @@ for vehicle in vehicles:
|
||||
|
||||
|
||||
for param_match in param_matches:
|
||||
p = Parameter(param_match[0])
|
||||
p = Parameter(vehicle.name+":"+param_match[0])
|
||||
print p.name + ' '
|
||||
field_text = param_match[1]
|
||||
#print "\n\nParameter: %s\n" % p.name
|
||||
|
Loading…
Reference in New Issue
Block a user