diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index b7404a0008d1a00bcde4ad8cc37c410f1eae7c1b..c5533f0b77cb4d21962e472d34b1fa95982272bb 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -3114,7 +3114,7 @@ but also ignore less noise 0 300 s - drivers/iridiumsbd + drivers/telemetry/iridiumsbd @@ -3655,17 +3655,41 @@ Used to calculate increased terrain random walk nosie due to movementtrue modules/mavlink - - Test parameter - This parameter is not actively used by the system. Its purpose is to allow testing the parameter interface on the communication level. - -1000 - 1000 - modules/mavlink - MAVLink airframe type 1 + 27 modules/mavlink + + Generic micro air vehicle + Fixed wing aircraft + Quadrotor + Coaxial helicopter + Normal helicopter with tail rotor + Ground installation + Operator control unit / ground control station + Airship, controlled + Free balloon, uncontrolled + Rocket + Ground rover + Surface vessel, boat, ship + Submarine + Hexarotor + Octorotor + Tricopter + Flapping wing + Kite + Onboard companion controller + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + Tiltrotor VTOL + VTOL reserved 2 + VTOL reserved 3 + VTOL reserved 4 + VTOL reserved 5 + Onboard gimbal + Onboard ADSB peripheral + Use/Accept HIL GPS message even if not in HIL mode @@ -3930,6 +3954,15 @@ Used to calculate increased terrain random walk nosie due to movementLockdown + + RC Loss Loiter Time (CASA Outback Challenge rules) + The amount of time in seconds the system should loiter at current position before termination. Only applies if NAV_RCL_ACT is set to 2 (CASA Outback Challenge rules). Set to -1 to make the system skip loitering. + -1.0 + s + 1 + 0.1 + modules/navigator + Set traffic avoidance mode Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders @@ -4503,6 +4536,7 @@ the vehicle will accelerate at this rate until the normal position control speed is 90 degrees. It should be lower than MPC_XY_CRUISE Applies only in AUTO modes (includes also RTL / hold / etc.) 1.0 + 20.0 m/s 2 1 @@ -5568,6 +5602,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 10 trim @@ -5606,6 +5644,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 11 trim @@ -5644,6 +5686,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 12 trim @@ -5682,6 +5728,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 13 trim @@ -5720,6 +5770,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 14 trim @@ -5758,6 +5812,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 15 trim @@ -5796,6 +5854,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 16 trim @@ -5834,6 +5896,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 17 trim @@ -5872,6 +5938,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 18 trim @@ -5911,6 +5981,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 1 trim @@ -5950,6 +6024,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 2 trim @@ -5989,6 +6067,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 3 trim @@ -6028,6 +6110,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 4 trim @@ -6066,6 +6152,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 5 trim @@ -6104,6 +6194,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 6 trim @@ -6142,6 +6236,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 7 trim @@ -6180,6 +6278,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 8 trim @@ -6218,6 +6320,10 @@ the setpoint will be capped to MPC_XY_VEL_MAX -1.0 1.0 modules/sensors + + Reverse + Normal + RC channel 9 trim @@ -6243,14 +6349,14 @@ the setpoint will be capped to MPC_XY_VEL_MAX modules/sensors - Cutoff frequency for the low pass filter on roll,pitch, yaw and throttle + Cutoff frequency for the low pass filter on roll, pitch, yaw and throttle Does not get set unless below RC_FLT_SMP_RATE/2 because of filter instability characteristics. 0.1 Hz modules/sensors - Sample rate of the remote control values for the low pass filter on roll,pitch, yaw and throttle + Sample rate of the remote control values for the low pass filter on roll, pitch, yaw and throttle Has an influence on the cutoff frequency precision. 1.0 Hz @@ -6688,17 +6794,6 @@ the setpoint will be capped to MPC_XY_VEL_MAX modules/commander - - - Loiter Time - The amount of time in seconds the system should loiter at current position before termination Set to -1 to make the system skip loitering - -1.0 - s - 1 - 0.1 - modules/navigator - - Threshold for selecting acro mode @@ -8080,14 +8175,14 @@ This is used for gathering replay logs for the ekf2 module LeddarOne rangefinder true - modules/sensors + drivers/distance_sensor/leddar_one Lidar-Lite (LL40LS) 0 2 true - modules/sensors + drivers/distance_sensor/ll40ls Disabled PWM @@ -8098,14 +8193,14 @@ This is used for gathering replay logs for the ekf2 module Maxbotix Soanr (mb12xx) true - modules/sensors + drivers/distance_sensor/mb12xx Lightware laser rangefinder (serial) 0 4 true - modules/sensors + drivers/distance_sensor/sf0x Disabled SF02 @@ -8120,7 +8215,7 @@ This is used for gathering replay logs for the ekf2 module 0 5 true - modules/sensors + drivers/distance_sensor/sf1xx Disabled SF10/a @@ -8134,7 +8229,7 @@ This is used for gathering replay logs for the ekf2 module Benewake TFmini laser rangefinder true - modules/sensors + drivers/distance_sensor/tfmini Thermal control of sensor temperature @@ -8149,7 +8244,7 @@ This is used for gathering replay logs for the ekf2 module 0 3 true - modules/sensors + drivers/distance_sensor/teraranger Disabled Autodetect