* msg: Add estinator information and warning events message (estimator_event_flags)
* ekf2: publish information and warning events
* logger: log estimator_event_flags
* update ecl submodule to latest
Co-authored-by: Daniel Agar <daniel@agar.ca>
- publish wind estimate only from EKF, and wind speeds from airspeed selector to new separate topic (airspeed_wind)
- rename message wind_estimate to wind
- publish wind from currently used ekf instance (ekf2selector)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- add command to request a message
- add gimbal attitude message
mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE
first implementation of new vmount input MavlinkGimbalV2
- setup class
- decode gimbal_manager_set_attitude in ControlData
add gimbal information message
add gimbal manager information and vehicle command ack
mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION
mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION
remove mavlink cmd handling from vmount input MavlinkGimbalV2
complete gimbal manager:
- send out fake gimbal_device_information for dummy gimbals
- complete ROI handling with nudging
small fixes
fix typos
cleanup
- gimbal device information
- flags lock
- check sanity of string
add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE
stream GimbalDeviceAttitudeStatus for dummy gimbals
- add uROB gimbal_attitude_status
- fill status in vmount output_rc for dummy gimbals not able to send the
status themselves
- stream mavlink GimbalDeviceAttitudeStatus
better handle the request for gimbal infomation request
clean up
bring gimbal information back on vmount init
add new gimbal message to mavlink normal stream
fix publication of gimbal device information
rename gimbal_attitude_status to gimbal_device_attitude_status
stream gimbal_manager_status at 5Hz
mavlink: send information only on request
Sending the information message once on request should now work and we
don't need to keep publishing it.
mavlink: debug output for now
make sure to copy over control data
mavlink: add missing copyright header, pragma once
mavlink: address review comments
mavlink: handle stream not updated
Our answer does not just depend on whether the stream was found but
whether we actually were able to send out an update.
mavlink: remove outdated comment
vmount: add option for yaw stabilization only
The stabilize flag is used for gimbals which do not have an internal IMU
and need the autopilot's attitude in order to do stabilization. These
gimbals are probably quite rare by now but it makes sense to keep the
functionality given it can e.g. be used by simple servo gimbals for
sensors other than highres cameras.
The stabilize flag can also be re-used for gimbals which are capable of
stabilizing pitch and roll but not absolute yaw (e.g. locked to North).
For such gimbals we can now set the param MNT_DO_STAB to 2.
We still support configuring which axes are stabilized by the
MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not
recommended anymore.
vmount: fix incorrect check for bit flag
mavlink_messages: remove debug message
Signed-off-by: Claudio Micheli <claudio@auterion.com>
use device id
remove debug print
gimbal attitude fix mistake
clang tidy fix
split:
- gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude
- gimbal_information -> gimbal_device_informatio, gimbal_manager_information
add gimbal protocol messages to rtps msg ids
support set attitude for gimbal directly speaking mavlink
clean up gimbal urob messages
vmount: address a few small review comments
vmount: split output into v1 and v2 protocol
This way we can continue to support the MAVLink v1 protocol. Also, we
don't send the old vehicle commands when actually using the new v2
protocol.
vmount: config via ctor instead of duplicate param
vmount: use loop to poll all topics
Otherwise we might give up too soon and miss some data, or run too fast
based on commands that have nothing to do with the gimbal.
typhoon_h480: use gimbal v2 protocol, use yaw stab
Let's by default use the v2 protocol with typhoon_h480 and enable yaw
lock mode by stabilizing yaw.
- new heater_status logging message
- run continously at low rate until configured sensor is found
- fix px4io fd bugs (fd open/close/ioctl must be same thread)
- control allocation module with multirotor, VTOL standard, and tiltrotor support
- angular_velocity_controller
- See https://github.com/PX4/PX4-Autopilot/pull/13351 for details
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Roman Bapst <bapstroman@gmail.com>
- log all estimator (ekf2) flags as separate booleans in a new dedicated low rate message (only publishes at 1 Hz or immediately on any change)
- this is a bit verbose, but it avoids the duplicate bit definitions we currently have across PX4 msgs, ecl analysis script, flight review, and many other custom tools and it's much easier for casual log review in FlightPlot, PlotJuggler, csv, etc
- for compatibility I've left estimator_status filter_fault_flags, innovation_check_flags, and solution_status_flags in place, but they can gradually be removed as tooling is updated
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
- split out switches from manual_control_setpoint into new message manual_control_switches
- manual_control_switches published at minimal rate (~ 1 Hz) or immediately on change
- simple switch debounce in rc_update (2 consecutive identical decodes required)
- manual_control_switches logged at full rate rather than sampled at (5-10% of messages logged)
- manual_control_setpoint publish at minimal rate unless changing
- commander handle landing gear switch for manual modes
- processing of mode_slot and mode_switch is now split so we only do one or the other (not both)
- a future step will be to finally drop mode_switch and accompanying switches entirely
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- ekf2 can now run in multi-instance mode (currently up to 9 instances)
- in multi mode all estimates are published to alternate topics (eg estimator_attitude instead of vehicle_attitude)
- new ekf2 selector runs in multi-instance mode to monitor and compare all instances, selecting a primary (eg N x estimator_attitude => vehicle_attitude)
- sensors module accel & gyro inconsistency checks are now relative to the mean of all instances, rather than the current primary (when active ekf2 selector is responsible for choosing primary accel & gyro)
- existing consumers of estimator_status must check estimator_selector_status to select current primary instance status
- ekf2 single instance mode is still fully supported and the default
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
- mavlink messages DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT move to separate stream headers and don't include if CONSTRAINED_FLASH
- mavlink receiver DEBUG/DEBUG_FLOAT_ARRAY/DEBUG_VECT/NAMED_VALUE_FLOAT handling excluded if CONSTRAINED_FLASH
- msg: skip debug_array.msg, debug_key_value.msg, debug_value.msg, debug_vect.msg if CONSTRAINED_FLASH
- new sensors work item that subscribes to N x sensor_gps and publishes vehicle_gps_position
- blending is now configurable with SENS_GPS_MASK and SENS_GPS_TAU
Co-authored-by: Jacob Crabill <jacob@volans-i.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
- inconsistency checks now run continuously instead of only preflight
- keep inconsistencies for all sensors
- add per sensor data validator state as overall health flag
- IMU integration move from drivers (PX4Accelerometer/PX4Gyroscope) to sensors/vehicle_imu
- sensors: voted_sensors_update now consumes vehicle_imu
- delete sensor_accel_integrated, sensor_gyro_integrated
- merge sensor_accel_status/sensor_gyro_status into vehicle_imu_status
- sensors status output minor improvements (ordering, whitespace, show selected sensor device id and instance)
* msg: Add EKF-GSF yaw estimator logging data
* ecl: update to version with EKF-GSF yaw estimator
* ekf2: Add param control and logging for EKF-GSF yaw estimator
* logger: Add logging for EKF-GSF yaw esimtator
with measurement noise auto-tuning
The purpose of this estimator is to improve land detection and vertical
velocity feedforward
Recovery strategy:
This is required when the setpoint suddenly changes in air or that the
EKF is diverging. A lowpassed test ratio is used as a trigger for the recovery logic
Also, a lowpassed residual is used to estimate the steady-state value
and remove it when estimating the accel noise to avoid increasing the
accel noise when the redisual is caused by an offset.
- introduces parameter IMU_DGYRO_CUTOFF to configure the angular acceleration low pass filter
- the angular acceleration is computed by differentiating angular velocity after the notch filter (IMU_GYRO_NF_FREQ & IMU_GYRO_NF_BW) is applied
Co-authored-by: Julien Lecoeur <jlecoeur@users.noreply.github.com>
- split out integrated data into new standalone messages (sensor_accel_integrated and sensor_gyro_integrated)
- publish sensor_gyro at full rate and remove sensor_gyro_control
- limit sensor status publications to 10 Hz
- remove unused accel/gyro raw ADC fields
- add device IDs to sensor_bias and sensor_correction
- vehicle_angular_velocity/vehicle_acceleration: check device ids before using bias and corrections