mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
* sensors: move GPS antenna offsets to per-receiver parameters
Move antenna position configuration from the single EKF2_GPS_POS_X/Y/Z
parameter set into per-receiver SENS_GPS{0,1}_OFF{X,Y,Z} parameters in
the sensors module. Each offset slot is matched to a physical receiver
by device ID (SENS_GPS{0,1}_ID), falling back to uORB instance index
when no IDs are configured.
The antenna offset is now carried through the SensorGps uORB message
and blended alongside other GPS states when multi-receiver blending is
active, so EKF2 receives the correct lever arm for whichever receiver
(or weighted combination) is selected.
- Add antenna_offset_{x,y,z} fields to SensorGps.msg
- Remove EKF2_GPS_POS_X/Y/Z params; EKF2 reads offset from gnssSample
- Add SENS_GPS{0,1}_ID and SENS_GPS{0,1}_OFF{X,Y,Z} params (module.yaml)
- Blend antenna offsets in GpsBlending (weighted average)
- Add unit tests for single, blended, and failover antenna offset cases
- Migrate params.c to module.yaml for the vehicle_gps_position module
* sensors: gps_blending: add asymmetric weight and fallthrough offset tests
Add two additional antenna offset test cases:
- dualReceiverAsymmetricWeightAntennaOffset: verify that unequal eph
values produce correctly skewed blend weights (0.8/0.2) and that the
output antenna offset reflects the weighted average
- blendingFallthroughAntennaOffset: verify that when blending is enabled
but can_do_blending evaluates false (eph=0), the non-blending path
correctly assigns the selected receiver's antenna offset
* feat(param_translation): translate EKF2_GPS_POS_ to SENS_GPS0_OFF_
* fix(msgs): proper formatting
* chore(msg): 0 if invalid/unknown
* fix(ROMFS): migrate EKF2_GPS_POS_ params
* fix(docs): migrate EKF2_GPS_POS_ params
* fix(blending): unsigned param
* Update msg/SensorGps.msg
Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com>
* fix(sensors/gps): remove 'values:' tag in module.yaml
* fix(sensors/gps): unsigned instance index
* fix(blending): restore const on gps_blend_states()
Move antenna offset blending into blend_gps_data() where the
weights are computed, keeping gps_blend_states() const.
* fix(sensors/gps): fix msg annotation and restore SENS_GPS_PRIME values
Remove incorrect @invalid NaN annotation from antenna offset fields
(0.0 default is correct, not a sentinel). Restore values tag for
SENS_GPS_PRIME so QGC shows a dropdown.
* fix(gps_blending): fix pre-existing bug to clear _gps_updated flags
The loop iterates over i but always clears gps_select_index. The intent is to clear
all updated flags, but only the selected one gets cleared (N times)
* test(gps_blending): add stale update flag regression test
112 lines
3.1 KiB
Bash
112 lines
3.1 KiB
Bash
#!/bin/sh
|
|
#
|
|
# @name PX4 Vision Dev Kit v1
|
|
#
|
|
# @type Quadrotor x
|
|
# @class Copter
|
|
#
|
|
# @board px4_fmu-v2 exclude
|
|
# @board bitcraze_crazyflie exclude
|
|
# @board px4_fmu-v6x exclude
|
|
# @board ark_fmu-v6x exclude
|
|
#
|
|
|
|
. ${R}etc/init.d/rc.mc_defaults
|
|
|
|
# Commander Parameters
|
|
param set-default COM_DISARM_LAND 0.5
|
|
|
|
# EKF2 parameters
|
|
param set-default EKF2_DRAG_CTRL 1
|
|
param set-default EKF2_IMU_POS_X 0.02
|
|
param set-default SENS_GPS0_OFFX 0.055
|
|
param set-default SENS_GPS0_OFFZ -0.15
|
|
param set-default EKF2_MIN_RNG 0.03
|
|
param set-default EKF2_OF_CTRL 1
|
|
param set-default EKF2_OF_POS_X 0.055
|
|
param set-default EKF2_OF_POS_Y 0.02
|
|
param set-default EKF2_OF_POS_Z 0.065
|
|
param set-default EKF2_REQ_HDRIFT 0.3
|
|
param set-default EKF2_REQ_SACC 1
|
|
param set-default EKF2_REQ_VDRIFT 0.3
|
|
param set-default EKF2_RNG_A_HMAX 8
|
|
param set-default EKF2_RNG_A_VMAX 2
|
|
param set-default EKF2_RNG_POS_X 0.055
|
|
param set-default EKF2_RNG_POS_Y -0.01
|
|
param set-default EKF2_RNG_POS_Z 0.065
|
|
param set-default EKF2_PCOEF_XP -0.25
|
|
param set-default EKF2_PCOEF_YN -0.55
|
|
param set-default EKF2_PCOEF_YP -0.55
|
|
|
|
# MAVLink parameters
|
|
param set-default MAV_0_CONFIG 101
|
|
param set-default MAV_1_CONFIG 102
|
|
param set-default MAV_1_RATE 80000
|
|
param set-default MAV_1_MODE 9
|
|
param set-default SER_TEL1_BAUD 921600
|
|
|
|
# Vehicle attitude PID tuning
|
|
param set-default MC_ACRO_P_MAX 200
|
|
param set-default MC_ACRO_R_MAX 200
|
|
param set-default MC_ACRO_Y_MAX 150
|
|
param set-default MC_PITCHRATE_D 0.0015
|
|
param set-default MC_ROLLRATE_D 0.0015
|
|
param set-default MC_YAWRATE_P 0.3
|
|
|
|
# Position Control Tuning
|
|
param set-default CP_DIST 6
|
|
param set-default MPC_ACC_DOWN_MAX 5
|
|
param set-default MPC_ACC_HOR_MAX 10
|
|
param set-default MPC_MAN_Y_MAX 120
|
|
param set-default MPC_THR_HOVER 0.3
|
|
param set-default MPC_VEL_MANUAL 5
|
|
param set-default MPC_XY_VEL_MAX 5
|
|
param set-default MPC_XY_VEL_P_ACC 1.58
|
|
param set-default MPC_XY_TRAJ_P 0.3
|
|
param set-default MPC_Z_TRAJ_P 0.3
|
|
param set-default MPC_Z_VEL_P_ACC 5
|
|
param set-default MPC_Z_VEL_I_ACC 3
|
|
param set-default MPC_LAND_ALT1 3
|
|
param set-default MPC_LAND_ALT2 1
|
|
param set-default CP_GO_NO_DATA 1
|
|
|
|
# Navigator Parameters
|
|
param set-default NAV_ACC_RAD 2
|
|
|
|
# RTL Parameters
|
|
param set-default RTL_DESCEND_ALT 5
|
|
param set-default RTL_RETURN_ALT 5
|
|
|
|
# Sensors Parameters
|
|
param set-default SENS_CM8JL65_CFG 104
|
|
param set-default SENS_FLOW_MAXHGT 25
|
|
param set-default SENS_FLOW_MINHGT 0.5
|
|
param set-default IMU_GYRO_CUTOFF 100
|
|
param set-default SENS_EN_PMW3901 1
|
|
|
|
# Power Parameters
|
|
param set-default BAT1_N_CELLS 4
|
|
param set-default BAT1_A_PER_V 36.364
|
|
param set-default BAT1_V_DIV 18.182
|
|
|
|
param set-default THR_MDL_FAC 0.3
|
|
|
|
# Square quadrotor X PX4 numbering
|
|
param set-default CA_ROTOR_COUNT 4
|
|
param set-default CA_ROTOR0_PX 1
|
|
param set-default CA_ROTOR0_PY 1
|
|
param set-default CA_ROTOR1_PX -1
|
|
param set-default CA_ROTOR1_PY -1
|
|
param set-default CA_ROTOR2_PX 1
|
|
param set-default CA_ROTOR2_PY -1
|
|
param set-default CA_ROTOR2_KM -0.05
|
|
param set-default CA_ROTOR3_PX -1
|
|
param set-default CA_ROTOR3_PY 1
|
|
param set-default CA_ROTOR3_KM -0.05
|
|
|
|
# Outputs
|
|
param set-default PWM_AUX_FUNC1 101
|
|
param set-default PWM_AUX_FUNC2 102
|
|
param set-default PWM_AUX_FUNC3 103
|
|
param set-default PWM_AUX_FUNC4 104
|