diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 4b416c4cfbe5fbb143acf2cc56043d16770d5308..a397fab7ea1a85dc58cad8d30aaa9cefa8bd9b74 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -14,10 +14,10 @@ - + Simon Wilks <simon@px4.io> Flying Wing - https://pixhawk.org/platforms/planes/bormatec_camflyer_q + https://pixhawk.org/platforms/planes/z-84_wing_wing feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -25,10 +25,14 @@ right aileron throttle - + Simon Wilks <simon@px4.io> Flying Wing - https://pixhawk.org/platforms/planes/z-84_wing_wing + + + Simon Wilks <simon@px4.io> + Flying Wing + https://pixhawk.org/platforms/planes/bormatec_camflyer_q feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -36,6 +40,10 @@ right aileron throttle + + Lorenz Meier <lorenz@px4.io> + Flying Wing + Thomas Gubler <thomas@px4.io>, Julian Oes <julian@px4.io> Flying Wing @@ -58,10 +66,6 @@ right aileron throttle - - Simon Wilks <simon@px4.io> - Flying Wing - Simon Wilks <simon@px4.io> Flying Wing @@ -77,10 +81,6 @@ right aileron throttle - - Lorenz Meier <lorenz@px4.io> - Flying Wing - @@ -169,38 +169,31 @@ - - Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io> + + Simon Wilks <simon@px4.io> Quadrotor Wide - - Anton Babushkin <anton@px4.io> + + Anton Matosov <anton.matosov@gmail.com> Quadrotor Wide Thomas Gubler <thomas@px4.io> Quadrotor Wide - - Simon Wilks <simon@px4.io> + + Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io> Quadrotor Wide - - Anton Matosov <anton.matosov@gmail.com> + + Anton Babushkin <anton@px4.io> Quadrotor Wide - - Lorenz Meier <lorenz@px4.io> - Quadrotor x - - - Lorenz Meier <lorenz@px4.io> + + Thomas Gubler <thomas@px4.io> Quadrotor x - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel James Goppert <james.goppert@gmail.com> @@ -209,12 +202,8 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Lorenz Meier <lorenz@px4.io> - Quadrotor x - - - Mark Whitehorn <kd0aij@gmail.com> + + James Goppert <james.goppert@gmail.com> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel @@ -227,28 +216,24 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Lorenz Meier <lorenz@px4.io> - Quadrotor x - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Pavel Kirienko <pavel@px4.io> + + Blankered Quadrotor x - - Thomas Gubler <thomas@px4.io> + + Lorenz Meier <lorenz@px4.io> Quadrotor x Andreas Antener <andreas@uaventure.com> Quadrotor x - - Blankered + + Lorenz Meier <lorenz@px4.io> Quadrotor x + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel Mark Whitehorn <kd0aij@gmail.com> @@ -257,13 +242,28 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - James Goppert <james.goppert@gmail.com> + + Mark Whitehorn <kd0aij@gmail.com> + Quadrotor x + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Pavel Kirienko <pavel@px4.io> + Quadrotor x + + + Lorenz Meier <lorenz@px4.io> Quadrotor x feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel + + Lorenz Meier <lorenz@px4.io> + Quadrotor x + @@ -271,6 +271,14 @@ + + Anton Babushkin <anton@px4.io> + Simulation + + + Thomas Gubler <thomas@px4.io> + Simulation + Lorenz Meier <lorenz@px4.io> Simulation @@ -283,25 +291,27 @@ Anton Babushkin <anton@px4.io> Simulation - - Anton Babushkin <anton@px4.io> - Simulation - - - Thomas Gubler <thomas@px4.io> - Simulation - Thomas Gubler <thomas@px4.io> Simulation - - Lorenz Meier <lorenz@px4.io> + + Andreas Antener <andreas@uaventure.com> Standard Plane + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + aileron + aileron + elevator + rudder + throttle + wheel + flaps - + Lorenz Meier <lorenz@px4.io> Standard Plane feed-through of RC AUX1 channel @@ -309,8 +319,8 @@ feed-through of RC AUX3 channel aileron elevator - rudder - throttle + throttle + rudder flaps @@ -325,17 +335,11 @@ rudder flaps - + Lorenz Meier <lorenz@px4.io> Standard Plane - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - aileron - elevator - throttle - + Lorenz Meier <lorenz@px4.io> Standard Plane feed-through of RC AUX1 channel @@ -343,30 +347,22 @@ feed-through of RC AUX3 channel aileron elevator - throttle - rudder + rudder + throttle flaps - - Andreas Antener <andreas@uaventure.com> + + Lorenz Meier <lorenz@px4.io> Standard Plane feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel aileron - aileron - elevator - rudder - throttle - wheel - flaps + elevator + throttle - - Simon Wilks <simon@uaventure.com> - Standard VTOL - Simon Wilks <simon@uaventure.com> Standard VTOL @@ -383,6 +379,10 @@ Andreas Antener <andreas@uaventure.com> Standard VTOL + + Simon Wilks <simon@uaventure.com> + Standard VTOL + @@ -407,11 +407,11 @@ - + Roman Bapst <roman@px4.io> VTOL Quad Tailsitter - + Roman Bapst <roman@px4.io> VTOL Quad Tailsitter @@ -421,6 +421,10 @@ Roman Bapst <roman@px4.io> VTOL Tiltrotor + + Samay Siga <samay_s@icloud.com> + VTOL Tiltrotor + diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index e9b1495288b7c2d5abc7525284a178bf10cff06c..6b3a2928cd084ac20edd2673b6674cb5a06db315 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -357,7 +357,7 @@ velocity 0.01 modules/systemlib - + Number of cells Defines the number of cells the attached battery consists of. S @@ -370,6 +370,7 @@ velocity 15S Battery 14S Battery 16S Battery + Unconfigured 3S Battery 2S Battery 5S Battery @@ -392,16 +393,6 @@ velocity - - Camera trigger Interface - Selects the trigger interface - true - drivers/camera_trigger - - GPIO - Seagull MAP2 (PWM) - - Camera trigger interval This parameter sets the time between two consecutive trigger events @@ -445,7 +436,7 @@ velocity Distance, mission controlled - + Camera trigger pin Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6) 1 @@ -688,6 +679,31 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action + + Airfield home Lat + Latitude of airfield home waypoint + -900000000 + 900000000 + deg * 1e7 + modules/navigator + + + Airfield home Lon + Longitude of airfield home waypoint + -1800000000 + 1800000000 + deg * 1e7 + modules/navigator + + + Airfield home alt + Altitude of airfield home waypoint + -50 + m + 1 + 0.5 + modules/navigator + Comms hold wait time The amount of time in seconds the system should wait at the comms hold waypoint @@ -747,31 +763,6 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action modules/navigator - - Airfield home Lat - Latitude of airfield home waypoint - -900000000 - 900000000 - deg * 1e7 - modules/navigator - - - Airfield home Lon - Longitude of airfield home waypoint - -1800000000 - 1800000000 - deg * 1e7 - modules/navigator - - - Airfield home alt - Altitude of airfield home waypoint - -50 - m - 1 - 0.5 - modules/navigator - @@ -833,10 +824,21 @@ Assumes measurement is timestamped at trailing edge of integration period Integer bitmask controlling GPS checks - Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required GDoP set by EKF2_REQ_GDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check can only be used if the vehciel is stationary during alignment. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check can only be used if the vehciel is stationary during alignment. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT + Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required GDoP set by EKF2_REQ_GDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check can only be used if the vehicle is stationary during alignment. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check can only be used if the vehicle is stationary during alignment. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check can only be used if the vehicle is stationary during alignment. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT 0 511 modules/ekf2 + + Min sat count (EKF2_REQ_NSATS) + Min GDoP (EKF2_REQ_GDOP) + Max horizontal position error (EKF2_REQ_EPH) + Max vertical position error (EKF2_REQ_EPV) + Max speed error (EKF2_REQ_SACC) + Max horizontal position rate (EKF2_REQ_HDRIFT) + Max vertical position rate (EKF2_REQ_VDRIFT) + Max horizontal speed (EKF2_REQ_HDRIFT) + Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) + Required EPH to use GPS @@ -1025,10 +1027,15 @@ Assumes measurement is timestamped at trailing edge of integration period Integer bitmask controlling handling of magnetic declination - Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observaton when 3-axis magnetometer fusion is being used. + Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used. 0 7 modules/ekf2 + + use geo_lookup declination + save EKF2_MAG_DECL on disarm + use declination as an observation + Type of magnetometer fusion @@ -1077,10 +1084,17 @@ Assumes measurement is timestamped at trailing edge of integration period Integer bitmask controlling data fusion and aiding methods - Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion * + Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion 0 28 modules/ekf2 + + use GPS + use optical flow + inhibit IMU bias estimation + vision position fusion + vision yaw fusion + Determines the primary source of height data used by the EKF @@ -2324,11 +2338,6 @@ but also ignore less noise - - Accelerometer integration for prediction - - modules/local_position_estimator - Optical flow z offset from center -1 @@ -2384,21 +2393,21 @@ but also ignore less noise 3 modules/local_position_estimator - - Accelerometer xy standard deviation - Data sheet sqrt(Noise power) = 150ug/sqrt(Hz) std dev = (150*9.8*1e-6)*sqrt(1000 Hz) m/s^2 Since accels sampled at 1000 Hz. should be 0.0464 + + Accelerometer xy noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. 0.00001 2 - m/s^2 + m/s^2/srqt(Hz) 4 modules/local_position_estimator - - Accelerometer z standard deviation - (see Accel x comments) + + Accelerometer z noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) 0.00001 2 - m/s^2 + m/s^2/srqt(Hz) 4 modules/local_position_estimator @@ -2415,7 +2424,7 @@ but also ignore less noise modules/local_position_estimator - + GPS delay compensaton 0 0.4 @@ -2423,16 +2432,16 @@ but also ignore less noise 2 modules/local_position_estimator - - GPS xy standard deviation + + Minimum GPS xy standard deviation, uses reported EPH if greater 0.01 5 m 2 modules/local_position_estimator - - GPS z standard deviation + + Minimum GPS z standard deviation, uses reported EPV if greater 0.01 200 m @@ -2440,7 +2449,8 @@ but also ignore less noise modules/local_position_estimator - GPS xy velocity standard deviation + GPS xy velocity standard deviation. +EPV used if greater than this value 0.01 2 m/s @@ -2456,7 +2466,7 @@ but also ignore less noise modules/local_position_estimator - GPS max eph + Max EPH allowed for GPS initialization 1.0 5.0 m @@ -2464,7 +2474,7 @@ but also ignore less noise modules/local_position_estimator - GPS max epv + Max EPV allowed for GPS initialization 1.0 5.0 m @@ -2500,16 +2510,18 @@ but also ignore less noise 3 modules/local_position_estimator - + Position propagation noise density + Increase to trust measurements more. Decrease to trust model more. 0 1 m/s/sqrt(Hz) 8 modules/local_position_estimator - + Velocity propagation noise density + Increase to trust measurements more. Decrease to trust model more. 0 1 (m/s)/s/sqrt(Hz) @@ -2556,6 +2568,30 @@ but also ignore less noise 8 modules/local_position_estimator + + Cut frequency for state publication + 5 + 1000 + Hz + 0 + modules/local_position_estimator + + + Required xy standard deviation to publish position + 0.3 + 5.0 + m + 1 + modules/local_position_estimator + + + Required z standard deviation to publish altitude/ terrain + 0.3 + 5.0 + m + 1 + modules/local_position_estimator + @@ -2690,6 +2726,48 @@ but also ignore less noise Land at current position + + Loiter radius (FW only) + Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only). + 25 + 1000 + m + 1 + 0.5 + modules/navigator + + + Acceptance Radius + Default acceptance radius, overridden by acceptance radius of waypoint if set. + 0.05 + 200.0 + m + 1 + 0.5 + modules/navigator + + + Set data link loss failsafe mode + The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. + modules/navigator + + Loiter + Disabled + Land at current position + Return to Land + + + + Set RC loss failsafe mode + The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. + modules/navigator + + Loiter + Disabled + Land at current position + Return to Land + + Take-off altitude This is the minimum altitude the system will take off to. @@ -2779,48 +2857,6 @@ but also ignore less noise modules/navigator - - Loiter radius (FW only) - Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only). - 25 - 1000 - m - 1 - 0.5 - modules/navigator - - - Acceptance Radius - Default acceptance radius, overridden by acceptance radius of waypoint if set. - 0.05 - 200.0 - m - 1 - 0.5 - modules/navigator - - - Set data link loss failsafe mode - The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. - modules/navigator - - Loiter - Disabled - Land at current position - Return to Land - - - - Set RC loss failsafe mode - The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. Setting this parameter to 4 will enable CASA Outback Challenge rules, which are only recommended to participants of that competition. - modules/navigator - - Loiter - Disabled - Land at current position - Return to Land - - @@ -3587,47 +3623,59 @@ but also ignore less noise - - Invert direction of aux output channel 1 - Set to 1 to invert the channel, 0 for default direction. - + + Set the minimum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for industry default or 900 to increase servo travel. + 800 + 1400 + us true - drivers/px4fmu + modules/sensors - - Invert direction of aux output channel 2 - Set to 1 to invert the channel, 0 for default direction. - + + Set the maximum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for industry default or 2100 to increase servo travel. + 1600 + 2200 + us true - drivers/px4fmu + modules/sensors - - Invert direction of aux output channel 3 - Set to 1 to invert the channel, 0 for default direction. - + + Set the disarmed PWM for MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 + us true - drivers/px4fmu + modules/sensors - - Invert direction of aux output channel 4 - Set to 1 to invert the channel, 0 for default direction. - + + Set the minimum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for default or 900 to increase servo travel + 800 + 1400 + us true - drivers/px4fmu + modules/sensors - - Invert direction of aux output channel 5 - Set to 1 to invert the channel, 0 for default direction. - + + Set the maximum PWM for the MAIN outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for default or 2100 to increase servo travel + 1600 + 2200 + us true - drivers/px4fmu + modules/sensors - - Invert direction of aux output channel 6 - Set to 1 to invert the channel, 0 for default direction. - + + Set the disarmed PWM for AUX outputs + IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 + us true - drivers/px4fmu + modules/sensors Invert direction of main output channel 1 @@ -3691,59 +3739,47 @@ but also ignore less noise drivers/px4io - - Set the minimum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for industry default or 900 to increase servo travel. - 800 - 1400 - us + + Invert direction of aux output channel 1 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu - - Set the maximum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for industry default or 2100 to increase servo travel. - 1600 - 2200 - us + + Invert direction of aux output channel 2 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu - - Set the disarmed PWM for MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. - 0 - 2200 - us + + Invert direction of aux output channel 3 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu - - Set the minimum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 1000 for default or 900 to increase servo travel - 800 - 1400 - us + + Invert direction of aux output channel 4 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu - - Set the maximum PWM for the MAIN outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. Set to 2000 for default or 2100 to increase servo travel - 1600 - 2200 - us + + Invert direction of aux output channel 5 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu - - Set the disarmed PWM for AUX outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE THE SYSTEM TO PUT CHANGES INTO EFFECT. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. - 0 - 2200 - us + + Invert direction of aux output channel 6 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4fmu @@ -4162,33 +4198,6 @@ but also ignore less noise - - Roll trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - - - Pitch trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - - - Yaw trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 - 2 - 0.01 - modules/commander - RC Channel 1 Minimum Minimum value for RC channel 1 @@ -5295,6 +5304,33 @@ but also ignore less noise 2000 modules/sensors + + Roll trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + + + Pitch trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + + + Yaw trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + modules/commander + @@ -6455,13 +6491,6 @@ This is used for gathering replay logs for the ekf2 module - - RGB Led brightness limit - Set to 0 to disable, 1 for minimum brightness up to 15 (max) - 0 - 15 - drivers/rgbled - Auto-start script index CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system. @@ -6549,8 +6578,19 @@ This is used for gathering replay logs for the ekf2 module sdlog2 (default) + + RGB Led brightness limit + Set to 0 to disable, 1 for minimum brightness up to 15 (max) + 0 + 15 + drivers/rgbled + + + TEST_PARAMS + systemcmds/tests + TEST_MIN modules/controllib_test @@ -6599,10 +6639,6 @@ This is used for gathering replay logs for the ekf2 module TEST_DEV modules/controllib_test - - TEST_PARAMS - systemcmds/tests - @@ -6634,78 +6670,6 @@ This is used for gathering replay logs for the ekf2 module - - Target throttle value for pusher/puller motor during the transition to fw mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Maximum allowed down-pitch the controller is able to demand. This prevents large, negative -lift values being created when facing strong winds. The vehicle will use the pusher motor -to accelerate forward if necessary - 0.0 - 45.0 - modules/vtol_att_control - - - Fixed wing thrust scale for hover forward flight - Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. - 0.0 - 2.0 - modules/vtol_att_control - - - QuadChute - Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL - 0.0 - 200.0 - modules/vtol_att_control - - - Position of tilt servo in mc mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Position of tilt servo in transition mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Position of tilt servo in fw mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Duration of front transition phase 2 - Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. - 0.1 - 5.0 - s - 3 - 0.01 - modules/vtol_att_control - - - The channel number of motors that must be turned off in fixed wing mode - 0 - 12345678 - 0 - 1 - modules/vtol_att_control - VTOL number of engines 0 @@ -6892,6 +6856,78 @@ to accelerate forward if necessary 1 modules/vtol_att_control + + Position of tilt servo in mc mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Position of tilt servo in transition mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Position of tilt servo in fw mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Duration of front transition phase 2 + Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. + 0.1 + 5.0 + s + 3 + 0.01 + modules/vtol_att_control + + + The channel number of motors that must be turned off in fixed wing mode + 0 + 12345678 + 0 + 1 + modules/vtol_att_control + + + Target throttle value for pusher/puller motor during the transition to fw mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control + + + Maximum allowed down-pitch the controller is able to demand. This prevents large, negative +lift values being created when facing strong winds. The vehicle will use the pusher motor +to accelerate forward if necessary + 0.0 + 45.0 + modules/vtol_att_control + + + Fixed wing thrust scale for hover forward flight + Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. + 0.0 + 2.0 + modules/vtol_att_control + + + QuadChute + Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL + 0.0 + 200.0 + modules/vtol_att_control + @@ -7149,21 +7185,49 @@ Maps the change of airspeed error to the acceleration setpoint - - EXFW_HDNG_P - examples/fixedwing_control + + SEG_TH2V_P + modules/segway - - EXFW_ROLL_P - examples/fixedwing_control + + SEG_TH2V_I + modules/segway - - EXFW_PITCH_P - examples/fixedwing_control + + SEG_TH2V_I_MAX + modules/segway - - RV_YAW_P - examples/rover_steering_control + + SEG_Q2V + modules/segway + + + Failsafe channel mapping + The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific rc channel to use + 0 + 18 + modules/sensors + + Channel 11 + Channel 10 + Channel 13 + Channel 12 + Channel 15 + Channel 14 + Channel 17 + Channel 16 + Channel 18 + Channel 1 + Unassigned + Channel 3 + Channel 2 + Channel 5 + Channel 4 + Channel 7 + Channel 6 + Channel 9 + Channel 8 + First flightmode slot (1000-1160) @@ -7291,49 +7355,21 @@ Maps the change of airspeed error to the acceleration setpoint Stabilized - - SEG_TH2V_P - modules/segway - - - SEG_TH2V_I - modules/segway + + EXFW_HDNG_P + examples/fixedwing_control - - SEG_TH2V_I_MAX - modules/segway + + EXFW_ROLL_P + examples/fixedwing_control - - SEG_Q2V - modules/segway + + EXFW_PITCH_P + examples/fixedwing_control - - Failsafe channel mapping - The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific rc channel to use - 0 - 18 - modules/sensors - - Channel 11 - Channel 10 - Channel 13 - Channel 12 - Channel 15 - Channel 14 - Channel 17 - Channel 16 - Channel 18 - Channel 1 - Unassigned - Channel 3 - Channel 2 - Channel 5 - Channel 4 - Channel 7 - Channel 6 - Channel 9 - Channel 8 - + + RV_YAW_P + examples/rover_steering_control diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index cf8b481afe0c507a8e90c2cc4f90609b5b2b0aec..3984a5f6c6092f790db721e8ebfdc688fb102843 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -312,6 +312,32 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData metaData->convertAndValidateRaw(0, false /* validate */, enumValue, errorString); metaData->addEnumInfo(tr("Disabled"), enumValue); + } else if (elementName == "bitmask") { + // doing nothing individual bits will follow anyway. May be used for sanity checking. + + } else if (elementName == "bit") { + bool ok = false; + unsigned char bit = xml.attributes().value("index").toString().toUInt(&ok); + if (ok) { + QString bitDescription = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "parameter value:" + << "index:" << bit << "description:" << bitDescription; + + if (bit < 31) { + QVariant bitmaskRawValue = 1 << bit; + QVariant bitmaskValue; + QString errorString; + if (metaData->convertAndValidateRaw(bitmaskRawValue, true, bitmaskValue, errorString)) { + metaData->addBitmaskInfo(bitDescription, bitmaskValue); + } else { + qCDebug(PX4ParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name() + << " type:" << metaData->type() << " value:" << bitmaskValue + << " error:" << errorString; + } + } else { + qCWarning(PX4ParameterMetaDataLog) << "Invalid value for bitmask, bit:" << bit; + } + } } else { qCDebug(PX4ParameterMetaDataLog) << "Unknown element in XML: " << elementName; }