Commit Graph

1469 Commits

Author SHA1 Message Date
Mathieu Bresciani 74a54b3b12
EKF2: improve resilience against incorrect mag data
- when GNSS is used require low mag heading innovations during
  horizontal acceleration (yaw observable) to validate the mag
- only fuse mag heading just enough to constrain the yaw estimate
  variance to a sane value. Leave enough uncertainty to allow for a
  correction when the yaw is observable through GNSS fusion
2023-08-17 09:55:15 -04:00
Daniel Agar d75bb62a65
ekf2: separate mag and mag heading control logic (#21212)
- split mag_3d into new standalone mag fusion and mag fusion allowed to update all states (full mag_3d)
 - new dedicated control logic for mag/mag_3d fusion and standalone mag heading fusion
 - if WMM available use for mag_I and mag_B init
 - mag states reset if external yaw reset (yaw estimator, GPS yaw, etc)
 - mag reset if declination changed (eliminate _mag_yaw_reset_req)
 - mag fusion (but not mag_hdg or mag_3d) can be active during gps_yaw or ev_yaw (if yaw aligned north)

Co-authored-by: bresch <brescianimathieu@gmail.com>
2023-08-04 10:39:16 -04:00
Daniel Agar 88e7452492
commander: collapse ArmStateMachine and simplify
- simplify vehicle_status.arming_state down to just armed and disarmed
    - ARMING_STATE_INIT doesn't matter
    - ARMING_STATE_STANDBY is effectively pre_flight_checks_pass
    - ARMING_STATE_STANDBY_ERROR not needed
    - ARMING_STATE_SHUTDOWN effectively not used (all the poweroff/shutdown calls loop forever in place)
    - ARMING_STATE_IN_AIR_RESTORE doesn't exist anymore
 - collapse ArmStateMachine into commander
     - all requests already go through Commander::arm() and Commander::dismarm()
 - other minor changes
     - VEHICLE_CMD_DO_FLIGHTTERMINATION undocumented (unused?) test command (param1 > 1.5f) removed
     - switching to NAVIGATION_STATE_TERMINATION triggers parachute command centrally (only if armed)

---------

Co-authored-by: Matthias Grob <maetugr@gmail.com>
2023-07-28 17:12:01 -04:00
bresch 72be724b86 ekf2: log mag inclination and strength for tuning 2023-07-24 10:16:37 -04:00
Beat Küng 133aeb10a6 mision: only run mission feasibility checks when mission updated
Instead of also when geofence/safe points updated.
This prevents reporting multiple times.
2023-07-24 13:10:31 +02:00
Beat Küng 16a144c00f navigator: use mission topic to notify about geofence & safe point changes
This avoids the need to regularly access dataman for checking.
2023-07-24 13:10:31 +02:00
Igor Mišić c40a38bd88 dataman: remove locking mechanism 2023-07-24 13:10:31 +02:00
Igor Mišić 208552fdab dataman: add DatamanClient with sync functions
Rework of dataman
2023-07-24 13:10:31 +02:00
Matthias Grob 83b832fdce ManualControl: fix case where mode switches unintentionally in air
Case: A vehicle is already operating but has no stick input or another
source than RC. When RC stick input is switched to either because it gets
first time available or as a fallback to joystick then the mode was
immediately changed to the switch position. This can lead to loss of
control e.g. when the vehicle is flying far away and the
mode switch of the RC is in some fully manual piloted mode.

I added tests to cover the cases where RC mode initialization is expected
and also unexpceted because the vehicle is already armed.
2023-07-13 12:00:35 +02:00
Sergei Grichine f000238987 SensorGps.msg: switch to double precision for lat/lon/alt
To match https://github.com/PX4/PX4-GPSDrivers/pull/132 - adding high precision RTK lat/lon/alt components
2023-07-13 07:50:09 +02:00
Loic Fernau f8c9be087b
drivers: rework NXP UWB driver (#21124)
* UWB driver rework that uses 2 UWB MKBoards - 1 as Controller (Initiator), one as Controllee (Anchor)

Co-authored-by: NXPBrianna <108274268+NXPBrianna@users.noreply.github.com>
2023-07-12 11:44:23 -04:00
Niklas Hauser 8fe65c6722 Driver: Refactor MCP23009 GPIO expander into uORB driver 2023-06-19 07:58:21 +02:00
alexklimaj acd19a0520 Ublox add UBX-RXM-RTCM for RTCM input status 2023-06-09 14:51:28 +12:00
mcsauder b8ad9bdbe5 Add magnetometer thermal compensation. 2023-06-07 12:07:29 -04:00
Christian Rauch e76c2b6a43
delete unused mavlink_px4.py & fix typos in VehicleCommand (#21332)
This file is not used anywhere neither in PX4-Autopilot, nor in the docs.

---------

Co-authored-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2023-04-20 07:50:58 +02:00
Silvan Fuhrer 460956fd33 TECS: revert altitude controller to old logic
- if the height rate input into TECS is finite, use that one to
update a velocity reference generator
- if the velocity reference generator reports position locked or
height rate input is not finite, then run altidue reference generator
- run altitude controller only if altitue is controlled

if height_rate_setpoint is set, only use that one to update altitdue trajectory

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-04-06 20:12:52 +02:00
Silvan Fuhrer dde656f4b1 TECS status: rename tecs_status.altitude_filtered to altitude_reference
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-04-06 20:12:52 +02:00
Silvan Fuhrer ac6c9c857a Gimbal: remove shutter and retraction handling
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-23 06:59:02 +01:00
Silvan Fuhrer 17cd65a239 Navigator: remove support for DO_SET_SERVO
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-16 11:55:45 +01:00
Silvan Fuhrer a1812dbde0 gimbal: move gimbal controls to new dedicated topic
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-16 11:55:45 +01:00
Silvan Fuhrer 1218d9b2fc mavlink_mission: remove support for DO_SET_CAMERA_ZOOM
Camera controls should not happen through the flight controller, and
the control allocation has no means of controlling the camera zoom.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-16 11:55:45 +01:00
Silvan Fuhrer b16f16598b VTOL: remove virtual actuator_controls and instead use virtual torque/thrust topics
MC/FW rate controller and auto tuner: remove actuator_controls

AirshipAttControl: remove actuator_controls

MulticopterLandDetector: remove actuator_controls

mavlink streams vfr_hud and high_latency2: remove actuator_controls

RoverPositionController: remove actuator_controls

UUVAttitudeController: remove actuator_controls

battery: use length of thrust_setpoint for throttle compensation

VehicleMagnetometer: use length of thrust_setpoint for throttle compensation

Signed-off-by: Silvan Fuhrer
2023-03-16 11:55:45 +01:00
AlexKlimaj e375e02974 Add GPS spoofing state 2023-03-14 20:28:32 -04:00
Matthias Grob f498b90c41 mode_requirements: add manual control for manual modes 2023-03-08 09:32:56 +01:00
Silvan Fuhrer 1e56d9c219 Rework flaps/spoilers logic
- remove deprecated actuator_controls[INDEX_FLAPS/SPOILERS/AIRBRAKES]
- use new topic normalized_unsigned_setpoint.msg (with instances flaps_setpoint
and spoilers_setpoint) to pass into control allocation
- remove flaps/spoiler related fields from attitude_setpoint topic
- CA: add possibility to map flaps/spoilers to any control surface
- move flaps/spoiler pitch trimming to CA (previously called DTRIM_FLAPS/SPOILER)
- move manual flaps/spoiler handling from rate to attitude controller

FW Position controller: change how negative switch readings are intepreted
for flaps/spoilers (considered negative as 0).

VTOL: Rework spoiler publishing in hover

- pushlish spoiler_setpoint.msg in the VTOL module if in hover
- also set spoilers to land configuration if in Descend mode

Allocation: add slew rate limit of 0.5 to flaps/spoilers configuration change

Instead of doing the flaps/spoilers slew rate limiting in the FW Position Controller
(which then only is applied in Auto flight), do it consistently over all flight
modes, so also for manual modes.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 22:43:41 +01:00
Silvan Fuhrer 16594bffa9 Rework landing gear logic
- remove deprecated actuator_controls[INDEX_LANDING_GEAR]
- remove dead code in mc rate controller that used to prevent it from being retracted
on the ground (anyway had no effect as it only affected the actuator_control[LANDING_GEAR]
which wasn't sent to the control allocation)
- for VTOLs handle deployment/retraction of landing gear in AUTO  as a MC (retract if
more than 2m above ground, deploy if WP is a landing WP), plus additionally when transition
flight task is called (ALTITUDE mode and higher)
- for FW in AUTO: add logic in FW Position Controller, depending on waypoint type mainly
- manual landing gear settings always come through (a manual command overrides a previous
auto command, and vice-versa)

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 22:43:41 +01:00
Silvan Fuhrer 4b54ddfe61 Remove INDEX_COLLECTIVE_TILT from actuator_controls and instead use new topic tiltrotor_extra_controls
Tiltrotor_extra_controls also contains collective thrust beside collective tilt, as passing a 3D
thrust setpoint vector beside the tilt is not feasible.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 22:43:41 +01:00
Eric Katzfey 5cade89499
Improve logging for Modal IO ESC (#21188)
- always publish esc_status
 - when enabled via MODAL_IO_VLOG param, enable actuator debug output

 - for modal_io commands, use ESC HW ID values instead of motor number for easier use
 - publish esc_status message for command line commands

 - Uncommented the code that fills in the cmdcount and power fields in the esc_status topic

---------

Co-authored-by: Travis Bottalico <travis@modalai.com>
2023-03-06 09:51:22 -05:00
Silvan Fuhrer dc4926dc4d remove WheelEncoders.msg
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 09:43:01 -05:00
Silvan Fuhrer 76116d79f9 TECS: remove umcommanded_descent flag
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-01 10:39:09 +01:00
Silvan Fuhrer 527225357b TECS: remove unused TECS_MODE_CLIMBOUT
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-01 10:39:09 +01:00
Silvan Fuhrer 526e066d9a Commander: rework GPS invalid warning to use estimator feedback instead of separate GPS quality thresholds
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-02-24 13:32:38 +01:00
Beat Küng 3f2336af32
navigator: add ModeCompleted signalling topic 2023-02-07 19:11:52 -05:00
Daniel Sahu fa6fda6cce
ekf2: new gravity observation (#21038)
Signed-off-by: Daniel M. Sahu <danielmohansahu@gmail.com>
2023-02-07 13:28:58 -05:00
Silvan Fuhrer 9b3a28dff5 Commander: add local_position_accuracy_low flag, incl. warning and RTL
Set this flag to true if local position is valid but accuracy low, such that
the operator can be warned before system switches to position-failure failsafe.
Additionally, switch to RTL if currently in Mission or Loiter to try to reach home
or fly out of GNSS-denied area.

Set low accuracy threshold to 50m by default for FW and VTOL.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-02-01 16:47:11 +01:00
Beat Küng b1709743f7 commander: add wind or flight time limit exceeded mode requirement
This prevents switching into any of these modes once the condition is set.
2023-02-01 08:48:09 +01:00
Hamish Willee f25abbc80a Fix magnetometer typo 2023-01-30 10:24:16 +01:00
Silvan Fuhrer d53d200aa5 Update msg/TecsStatus.msg
Co-authored-by: KonradRudin <98741601+KonradRudin@users.noreply.github.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 88ec117e59 TECS: rename tecs_status.altitude_filtered to altitude_sp_ref
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 06f4195663 PositionControllerStatus.msg: add comments
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer fc1c5da92c tecs_status.msg: add comments to states
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 148ffe4e25 add support for DO_CHANGE_ALTITUDE
Do the same as DO_REPOSITION wit only the altitude field populated
and MAV_DO_REPOSITION_FLAGS set, which means:
- switch to Loiter mode if not already in it
- set the current altitude to what is specified in the altitdue field,
keep current altitude setpoint otherwise
- keep current position setpoint
- fall back to current estimated position in case a position setpoint
is not finite

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-25 16:40:27 +01:00
bresch 6e30f8f5cb ekf2: use dedicated aid_src message for flow for terrain aiding 2023-01-21 15:31:19 -05:00
Daniel Agar 1aa8ec4537
drivers: initial VectorNav (VN-100, VN-200, VN-300) support 2023-01-20 19:09:30 -05:00
Jukka Laitinen 2985b5b9c2 msg/ActuatorTest.msg: Use default queue size the same as MAX_NUM_MOTORS
For the esc_calibration code, the actuator test is published for each motor
in a row. If the orb queue size is too small, messages are lost and not
received in mixer_module.

Set the default orb queue size of ActuatorTest high enough to keep the commands
for all motors in the queue.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2023-01-14 09:19:10 -05:00
Silvan Fuhrer 303b879748 VTOL/Commander: rename transition_failsafe to vtol_fixed_wing_system_failure
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Konrad f5524fa605 TECS: Combine both airspeed and airspeed derivative filters in TECS into one MIMO filter using a steady state Kalman filter. 2022-12-21 09:04:19 +01:00
Daniel Agar 54a32eb2f7
ekf2: EV overhaul yaw and position fusion (#20501)
- move EV yaw and EV position to new state machines
 - EV yaw and EV pos now configured via EKF2_EV_CTRL (migrated from EKF2_AID_MASK)
 - new EV position offset estimator to enable EV position while GPS position is active (no more EV pos delta fusion)
 - yaw_align now strictly means north (no more rotate external vision aid mask)
 - automatic switching between EV yaw, and yaw align north based on GPS quality
2022-12-20 10:23:56 -05:00
Zachary Lowell e4f641e9b5
Qurt qshell implementation (#20736) 2022-12-09 16:49:41 -05:00
Matthias Grob 331cb21dee manual_control_setpoint: change stick axes naming
In review it was requested to have a different name for
manual_control_setpoint.z because of the adjusted range.

I started to investigate what naming is most intuitive and found
that most people recognize the stick axes as roll, pitch, yaw, throttle.
It comes at no surprise because other autopilots
and APIs seem to share this convention.

While changing the code I realized that even within the code base
the axes are usually assigned to a variable with that name or
have comments next to the assignment clarifying the axes
using these names.
2022-11-28 19:25:55 +01:00