* MC_HTE: unitialize with hover_thrust parameter
* MC_HTE: constrain hover thrust setter between 0.1 and 0.9
* MC_HTE: integrate with land detector and velocity controller
* MCHoverThrustEstimator: Always publish an estimate even when not fusing measurements. This is required as the land detector and the position controller need to receive a hover thrust value.
* MC_HTE: use altitude agl threshold to start the estimator
local_position.z is relative to the origin of the EKF while dist_bottom
is above ground
Co-authored-by: bresch <brescianimathieu@gmail.com>
The implementation before this change had two timeouts, a hard-coded
timeout of 0.5 seconds as well as a by param configurable timeout with
certain failsafe actions set.
This change aims to fix two problems:
1. The hard-coded offboard timeout can be triggered easily with sped up
lockstep simulation. Since i t is hard-coded it can't be adapted to
the speed factor.
2. The offboard signal can time out but no action will be taken just
yet. This means we end up in an in-between stage where no warning or
failsafe action has happened yet, even though certain flags are set
to a timeout state.
This patch aims to fix this by unifying the two timeouts to the existing
configurable param. The convoluted double timeout logic is replaced by a
simple hysteresis.
For anyone that has previously not changed the default timeout param (0),
the param will now be changed to 0.5 seconds which reflects the
previously hardcoded time. For anyone with a specific timeout
configured, the behaviour should remain the same.
Also, going forward, timeouts lower than 0.5 seconds should be possible.
Sometimes in CI for VTOL we saw disarms before the spoolup and ramp were
over and the takeoff would actually happen. By raising the auto-disarm
time we should be able to work around this and get CI less flaky.
Channels belonging to a certain timer were not all grouped together.
This is required by the .first_channel_index and .last_channel_index data
members.
We introduce a new mixer geometry to solve the problem.
* add support for unmanned underwater vehicles:
* airframe uuv_generic + uuv_hippocammpus including mav_type = 12 for submarines
* mixer for UUVs with X-shaped thruster setup similar to quadcopter
* add module uuv_att_control for underwater robot attitude control
* add rc.uuv_defaults/apps for autostarting e.g. ekf2 and uuv_att_control app
- this is a new module for temperature compensation that consolidates the functionality previously handled in the sensors module (calculating runtime thermal corrections) and the events module (online thermal calibration)
- by collecting this functionality into a single module we can optionally disable it on systems where it's not used and save some flash (if disabled at build time) or memory (disabled at run time)
This reverts commit be35c4857b.
This would only work for integer math, so for simulation speed-up. For
speeds slower than realtime we need floating point.
- this is one of the last pieces of the system that still depend on DriverFramework
- add new SIM_GPS_NOISE_X parameter for optionally increasing the GPS noise multiplier (was previously a gpssim command line option)
- add SIM_x_BLOCK parameters to block sensor publication
- SIM_GPS_BLOCK
- SIM_ACCEL_BLOCK
- SIM_GYRO_BLOCK
- SIM_MAG_BLOCK
- SIM_BARO_BLOCK
- SIM_DPRES_BLOCK
* parameter and logic to commander for triggering failsafe from external automatic trigger system.
* logic to startup script for enabling ATS. Added uORB publishing to pwm_input module.
* Refactored out CDev usage from pwm_input and ll40ls. Refactored out ll40ls specifics from pwm_input and cleaned up dead code.
This target was never fully supported and is heavily dependent on a number of DriverFramework drivers that have no in tree equivalents (bebop bus, flow, rangefinder, etc). Deleting this will make it easier to fully drop DriverFramework shortly.
When running in HITL mode, pwm_out_sim publishes actuator_outputs.
px4io unconditionally publishes the uOrb actuator_outputs. When HITL
is configured, the px4io copy of the uOrb has all zeros.
The result is that there are two publications, one valid, and one
all-zeros. This causes the HIL_ACTUATOR_CONTROLS mavlink message
to be incorrect (all-zeros) and the SERVO_OUTPUTS_RAW mavlink
message to be inconsistent, as it takes the data from one or the
other uOrb randomly each cycle.
The fix is to let px4io know that HITL is in effect when it is
started, and modify px4io to suppress publication in this case.
This is a bigger more complicated fix than I would like, but I
think it is conceptually correct.
Signed-off-by: Nik Langrind <langrind@gmail.com>
* Draco-R sensor orientation correction
* LL40LS sensor is not stable during I2C probing. More trials have been implemented.
* px4flow execution has been removed as rc script already running it
* GPS LED script repaired
* Off ICM20608 due to some bug?
* Removed i2c speed adjustment due to SMBUS.
* ms5611 test2 does not exist
* Baud rate has changed.
* Draco-R airframe parameters are updated.
* IFO and Draco parameters are updated
* Draco-R sensor orientation corrected
* Draco-R DSHOT supports
-moved rc.mavlink to the boards optional rc additions (now it's called rc.board_mavlink) to handle board specific mavlink needs (mavlink over usb, ethernet, additional streams, etc.)
-mavlink module will be responsible to usb defaults, therefore less args are needed to be passed to mavlink module if one wants to use mavlink over usb.
-the way to check if connection is usb is by it's designated variable and not by config mode.
This change adds the line "param set RTL_TYPE 1" to the default init scripts for fixed wing. Similar to the other PR that sets default RTL_TYPE=1 for VTOLs, RTL_TYPE=1 should be default for normal fixed wings as well. Reference: https://github.com/PX4/Firmware/pull/12746/files
This new airspeed module does:
-runns an airspeed validator for every airspeed sensor present, which checks measurement validity and estimates an airspeed scale
-selects another airspeed sensor if for the current one a failure is detected
-estimates airspeed with groundspeed-windspeed if no valid airspeed sensor is present
-outputs airspeed_validated topic
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
It doesn't affect fixed wing flying anymore. I disabled it for the
deltaquad since I presume @sanderux prefers to have the feature disabled
even when flying in multicopter mode.
* Set/unset rcS vars at beginning and end of rcS script and reduce a few LOC checking SYS_AUTOCONFIG with improved logic.
* Restore current placement of set/unset vars in rcS script to leave only the SYS_AUTOCONFIG logic modification.
* Replace set AUTOCNF no after inadvertent deletion.
Updated the babyshark default parameters for improved flight performance,
as well as two MPC parameters in vtol_defaults for smoother hovering with VTOLS"
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Reduces clutter in the boot output (now that we have it in the log).
On omnibus for example we see:
ERROR [param] Parameter SENS_EN_BATT not found
ERROR [param] Parameter SENS_EN_LL40LS not found
ERROR [param] Parameter SENS_EN_LL40LS not found
ERROR [param] Parameter SENS_EN_MB12XX not found
ERROR [param] Parameter SENS_EN_PGA460 not found
ERROR [param] Parameter SENS_EN_SF1XX not found
ERROR [param] Parameter SENS_EN_TRANGER not found
When simulating with lockstep we can raise the speed by setting the env
variable `PX4_SIM_SPEED_FACTOR`. Some inputs like RC, MAVLink heartbeats
from a ground station, or offboard controls via MAVLink are still at the
normal speed which leads to timeouts getting detected in PX4.
To work around this issue we can automatically multiply the timeout
parameters by the speed factor.
This way we prevent a big dip due to TECS in altitude when the
transition happens at 10 m/s already. Apparently the rule of thumb
is to set this transition speed at the same as airspeed cruise speed.
Mark V19_VT_ROLLDIR @category system
Throttle down mavlink critical msg
Send 0 actuator_output for safety
VTOL: unset v1.9 roll direction safety check param for builtin airframes
This inversion matches the fixed sign in the commands generated
by the VTOL attitude controller.
This commit, combined with the previous commit, should have no effect.
For safety, it is recommended to check the direction of roll control
surfaces before flight.
A side-effect of the previous commit is that the integral is loaded up
during a flip, which leads to visible bounce-backs after a flip.
Reducing the I helps, but there's a trade-off and we'll need a better
solution.
Device port can be set via SENS_EN_CM8JL65 parameter:
SENS_EN_CM8JL65 = 0 -> Disabled
SENS_EN_CM8JL65 = 1 -> Enabled on TELEM2
SENS_EN_CM8JL65 = 2 -> Enabled on TELEM1
Signed-off-by: Claudio Micheli <claudio@auterion.com>
Setting PWM_DISARMED to 0 results in no PWM output to the ESC for the pusher motor.
Most ESCs start beeping endless in short intervals if they don't get a signal.
I remove changing this parameter which is 900 by default to always command the motor to stand still.
The startup file rc.board is copied to the build/../genromfs folder
after the pruning of the files happened. Thus, about 2000 bytes of
comments and whitespace were included in the ROMFS.
This commit moves pruning of the files in ROMFS to a separate cmake
custom command which happens after the ROMFS files have been copied and
the extra files have been added.
Testing showed that this change only affected the rc.board file as
expected.
tone_alarm was started before the parameters were loaded, and the first
tune was played before that as well. CBRK_BUZZER was then read as default,
ignoring the user-configured value.
We now start tone_alarm after we load the parameters. Note that a
previously published startup tone or SD card error will still be played.
* added a parameter for enabled the smart battery
* start tel1 and tel2 at 921600 and max rate
* turned up the max tx rate on mavlink streams for telem1 and telem2
* turned off mavlink stream for tel1 in 4250_teal. This is connected to TX1 FTDI UART and has issues.
* moved check to 4250 board ID to start mpu9250s for Teal airframe into fmuv4 rc.board.
* Integrated preliminary ICM20948 support into MPU9250 driver.
Fixed temperature conversion for MPU9250/ICM20948.
* Included missing check for PX4_I2C_OBDEV_MPU9250 in main.cpp.
* Added explicit bus for internal MPU9250 on Pixhawk 2.1 to avoid implicit start
of an externally attached device with wrong orientation.