This is a bigger refactor of vmount to clean it up and plug some holes
in functionality.
The changes include:
- Fixing/simplifying the test command.
- Changing the dependencies of the input and output classes to just the
parameter list.
- Adding a separate topic to publish gimbal v1 commands to avoid
polluting the vehicle_command topic.
- Removing outdated comments and author lists.
- Extracting the gimbal v2 "in control" notion outside into control_data
rather than only the v2 input.
If we receive gimbal_device_attitude_status by mavlink we should not
re-send it as we are already supposed to be forwarding mavlink traffic
from the gimbal to the ground station.
- move vehicle at reset detection ekf2 -> land_detector
- ekf_unit: reduce init period
- Fake fusion is when at rest is quite strong and makes the variance reduce rapidly. Reduce the amount of time we wait before checking if the variances are still large enough.
- ekf_unit: reduce minimum vel/pos variance required after init
- Fake pos fusion has a low observation noise, making the vel/pos variances reduce quickly.
Co-authored-by:: bresch <brescianimathieu@gmail.com>
The existing implementation has about 100ms difference to a reference clock. With the changes this error less than 25us.
- Use sensor_gps messages with hrt timestamps as RTC reference and not the system realtime clock. The PPS interrupt can then be aligned with the GPS clock system.
- Keep fallback based on system RTC when no PPS pulse was captured
- camera_trigger module always publishes the camera_trigger msg (independent of the camera feedback)
- Use camera_trigger msg and set the feedback flag
- Subscribing modules determine if the message is relevant based on the feedback message
CA: fix saturation computation
Since the CA matrix is normalized, the same scale applied to be used when using the effectiveness matrix
MCRateControl: use control_allocator_status to get saturation info
The arming button required some refactoring in order to support to
toggle arm/disarm using the vehicle_command. Otherwise manual_control
would have to subscribe to the arming topic and we would spread out the
logic again, and risk race conditions.
This is an intermediate solution to carry forward the initial state of
the mode slot. Basically, it allows that we start up in Stabilized but
switch to POSCTL as soon we have the required GPS.
This adds a selector class with unit tests.
The idea is to have a valid flag in manual_control_septoint and set that
according to the selection and/or timeout of manual_control_inputs.
* ekf2: make publishing of learned accel biases more robust
* ekf2: reset accel bias if calibration updated
* msg: add separate accel and gyro calibration counters
* ekf2: use separate accel and gyro calibration counters
* ekf2: rework logic to reset biases when calibration counters increment
* sensors: add saving of learned accel biases
* ekf2: generalized saving accel/gyro/mag in flight sensor calibration
* boards: holybro kakutef7 disable systemcmds/perf and systemcmds/top to save flash
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
- remove GPS failsafe mode
- for VTOL: transition to hover in Descend (unless NAV_FORCE_VT is not set)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- run airspeed scale estimation always, not in dedicated mode
- add option to apply scale automatically, with extra feasibility check
- add airspeed scale for all 3 possible airspeed instances
- clean up parameters
- add check for data stuck (non-changing airspeed data)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
1. The RTPS IDs are now automatically assigned to the topics
2. Only the topics that get defined to be sent or received in the urtps_bridge_topics.yaml (renamed, since now it doesn't contain IDs) receive the IDs
3. Any addition or removal on the urtps_bridge_topics.yaml file might update the topic IDs - this will require that the agent and the client ID list has to be in sync. This will further require a robustification of the way we check the IDs and the message definitions when starting the bridge.
This allows that all messages (not only timesync messages) that get received on the same system that sent them do not get parsed. As the microRTPS agent is built currently, this will only happen right now if someone sets the same UDP port to send and receive data, or by manually changing the agent topics (which were always autogenerated).
- naming consistency (estimator prefix as "namespace")
- only publish if baro is available and bias is changing as a small logging optimization
- avoid unnecessary copying (get const reference to status directly)
- trivial code style fixes
Only needed for Makefile-based builds:
gmake[3]: *** No rule to make target 'src/modules/flight_mode_manager/FlightTasks_generated.hpp', needed by 'events/px4.json'. Stop.
- sending protocol
- uorb event message & template methods for argument packing
- libevents submodule to send common events and handle json files
- cmake maintains a list of all (PX4) source files for the current build
(PX4 modules + libs), which is used to extract event metadata and
generate a json file
- change default FFT length (1024 -> 512)
- this doubles the update rate because half the number of samples are required for each
- decrease number of peaks (4 -> 3)
- so far 3 seems to be sufficient on most vehicles
- increase median filter window (3 -> 5)
- decrease SNR requirement (likely needs to be configurable)
* commander: send parachute command on termination
This sends the DO_PARACHUTE command to parachute component.
* commander: fix lying comments and printf
* commander: use one flag for termination triggered
This merges the duplicate flags _flight_termination_triggered and
_flight_flight_termination_printed.
* commander: correct variable name
* commander: always send tune with parachute
* commander: fix target_component for parachute cmd
The previous changes were wrong in that all commands were now sent to
the parachute component which doesn't make any sense. Of course only the
parachute command should be sent there.
Instead of only keeping track of the sequence ID of specific "supported"
components, we now keep track of any sysid/compid of an incoming
message. Before this change, unknown components (such as jMAVSim) would
completely screw up the mavlink message stats and create confusion (at
least in my case).
With this change we currently keep track of up to 8 other components.
Once we reach the limit, we will print a warning.
statfs accesses the file-system and can be blocking for an extended period. Since the SD card check is part of the preflight checks in the main thread of commander, it could block its execution and cause various issues. The SD card is only mounted in rcS during boot so the state will not change after the first check.
- rotates accel & gyro FIFO data before publication both to simplify downstream usage (including log review) and fix other issues
- to best handle int16_t data rotations are now either performed with swaps if possible, otherwise promoted to float, rotated using the full rotation matrix, then rounded back to int16_t
- fix sensors/vehicle_angular_velocity filter reset both with proper rotation and new calibration uncorrect helper
- in FIFO case filtering is done before calibration is applied, but we need to handle a possible reset from a completely different sensor (vehicle body angular velocity -> sensor frame uncorrected data)
- fully respect datasheet quality and shutter metrics for mode changes
- use MOTION pin for scheduling if available
- log light mode
- refactor common enable LED code
- respect read and write time delays
* 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>
- handle SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT with ORB_ID(trajectory_setpoint)
- FlightTaskOffboard not needed at all
- bypass position_setpoint_triplet entirely (start removing extraneous fields)
- simplify offboard_control_mode to map to supported control modes
- 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>
We should be using gimbal_manager_information and not
gimbal_device_information. Plus, this updates the fields and flags
according to the MAVLink changes.
- 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)
Instead of directly doing the link loss reaction which by default is RTL a delay
can be configured such that the drone first switches to hold and waits
for the link to be regained.
For some usecases like starting video recording on a companion computer or triggering a ROS based (offboard control) mission control execution the status of RC channel is needed in ROS(2). This allows the user to start/stop such functionalities from the RC transmitter.
Therefore InputRc to be changed accordingly.
add 'Set send: true' for id: 30
Add new DeviceBusType_SERIAL to Device::DeviceId union
Add DRV_DIST_DEVTYPE's for all distance sensors
Change distance_sensor_s.id to distance_sensor_s.device_id
Modify all distance_sensor drivers to apply 'proper' device_id
- 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>
- commander preflightcheck use estimator_sensor_bias message instead of EKF state index magic number
- ekf2 publish estimated bias limits in estimator_sensor_bias
- preflightcheck only error if bias estimate exceeds half of configured limit (delete COM_ARM_EKF_AB and COM_ARM_EKF_GB parameters)
- handle saving the mag bias per sensor (across all estimator instances using that mag) in sensors/vehicle_magnetometer
- this is now saving back to the actual mag calibration CAL_MAGn_OFF{X,Y,Z}
- ekf2 reset mag mag bias on any magnetometer or calibration change
- use Kalman filter scheme to update stored mag bias parameters using all available bias estimates for that sensor
Co-authored-by: Paul Riseborough <gncsolns@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>
Changed all 'NED' references to 'FRD'. Also cleaned up mixing of m/s/s and m/s^2 to use the latter. Corrected m/s/s to Pascals. Plus minor typos. Also made some minor cosmetic clean ups.
Co-authored-by: Robin <robin@Robins-MacBook-Pro-Work.local>
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>
- saves a small amount of work for the ekf2 selector in multi-EKF mode (visual_odometry_aligned now ignored)
- helps to distinguish the origin/purpose from vehicle_odometry and vehicle_visual_odometry
- 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>
- add new parameter `IMU_GYRO_FFT_EN` to start
- add 75% overlap in buffer to increase FFT update rate
- space out FFT calls (no more than 1 per cycle)
- increase `IMU_GYRO_FFT_MIN` default
- decrease main stack usage
- 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
- drivers/tone_alarm: move to ModuleBase and purge CDev (/dev/tone_alarm0)
- drivers/tone_alarm: only run on tune_control publication (or scheduled note) rather than continuously
- drivers/tone_alarm: use HRT to schedule tone stop (prevents potential disruption)
- msg/tune_control: add tune_id numbering
- systemcmds/tune_control: add "error" special case tune_id
- move all tune_control publication to new uORB::PublicationQueued<>
- start tone_alarm immediately after board defaults are loaded to fix potential startup issues
- for SITL (or other boards with no TONE output) print common messages (startup, error, etc)
- 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>
- vehicle_imu/vehicle_magnetometer add monotonically increasing `calibration_count` field so that downstream subscribers are aware of calibration changes
- inconsistency checks now run continuously instead of only preflight
- keep inconsistencies for all sensors
- add per sensor data validator state as overall health flag
- use proper Mavlink MAV_CMD_FIXED_MAG_CAL_YAW command for initiating magnetometer quick cal
- MAV_CMD_FIXED_MAG_CAL_YAW allows specifying the yaw and optionally latitude and longitude if the vehicle doesn't have GPS