- msg constant names now comply with ROS conventions:
uppercase alphanumeric characters with underscores for separating words
partially fix#19917
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
As per the discussion in #15331, fixed issue where stm32h7 chips
use hardware ECC bits in program memory that disallow overwriting
32-byte flash line that has already been written. As such,
this change allows for a variant implementation of the flashfs system
that uses more space in the flash entry header in order to
allow an entire line to be reserved for erasing an entry.
Signed-off-by: Taylor Nelms <tnelms@roboticresearch.com>
rtl state was getting reset on inactive, which meant that the state which triggered resuming e.g. mission landing would be overwritten, and the navigator mode would switch back and forth between rtl and mission. this commit:
1. moves the reset of rtl state to the on activation function (removing it from the on inactive function)
2. functionalizes the rtl state input to the rtl time estimator so that rtl time can still be calculated from state=none while inactive
This commit removes the additional airspeed check (airspeed for VTOLs in
hover below LNDFW_AIRSPD_MAX), as it is not a required condition in the
landed state (headwind blowing into the airspeed sensor won't stop
once on the gruond). In FW mode the check would make more sense, but there
the land detector is currently simply disabled.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- if using multi-EKF across all magnetometers then an instance of
vehicle_magnetometer is advertised immediately for every sensor_mag
instance
- this can become problematic if EKF2 multi-mag is enabled, but with
only 1 IMU (EKF2_MULTI_MAG) because you will be stuck with no magnetometer data
FW_LND_USETER defaulted to 1 and FW_LND_ABORT terrain based bits all enabled. why? because using a distance sensor is critical to detecting when to flare, and we want to force the user to actively disable these safety settings if they so choose, so that they understand the implications.
- new param, FW_LND_TER_REL
- fixing the glide slope helps keep the landing glide behavior steady (avoiding bumps in the altitude setpoint from e.g. trees)
- flare is still triggered via the distance sensor, if enabled by FW_LND_USETERR
when the vehicle did not track the slope well (e.g. at an offset above the track) and the altitude setpoint flattening on intersection with terrain, the throttle would spool up to smoothly intersect the newly flattened altitude setpoint, this could happen before the flare altitude was reached, which is bad. now the steady state glide behavior will be maintained, and flare can trigger at the appropriate time
- the target_sink_rate param could possibly constrain the maximum commanded sink rate to something less than that of the landing glide slope, which would make it impossible to track. this commit allows opening up the desired max sink rate up to the performance limits of the aircraft, if necessary, for the landing case
- landing slope/curve library removed
- flare curve removed (the position setpoints will not be tracked during a flare, and were being ignored by open-loop maneuvers anyway)
- flare curve replaced by simply commanding a constant glide slope to the ground from the approach entrance, and commanding a sink rate once below flaring alt
- flare is now time-to-touchdown -based to account for differing descent rates (e.g. due to wind)
- flare pitch limits and height rate commands are ramped in from the previous iteration's values at flare onset to avoid jumpy commands
- TECS controls all aspects of the auto landing airspeed and altitude/height rate, and is only constrained by pitch and throttle limits (lessening unintuitive open loop manuever overrides)
- throttle is killed on flare
- flare is the singular point of no return during landing
- lateral manual nudging of the touchdown point is configurable via parameter, allowing the operator to nudge (via remote) either the touchdown point itself (adjusting approach vector) or shifting the entire approach path to the left or right. this helps when GCS map or GNSS uncertainties set the aircraft on a slightly offset approach"
- refactor updateQuaternion() to compute the yaw jacobian directly (respecting the rotation sequence determination)
- fuseHeading()/fuseYaw321()/fuseYaw312() helpers are eliminated and now mag heading fusion and EV yaw fusion compute the innovation in place
- clear up logic for performing zero innovation heading fusion when quaternion variance exceeds threshold (no more _is_yaw_fusion_inhibited flag manipulation)
- when at rest continue fusing last static heading with very low variance even if other heading sources are active
We need to ensure the Dronecode logo is prominently displayed
and linked to the PX4 brand for trademark protection of PX4 and Dronecode.
If you have any questions about this, please feel free to reach out directly to me.
- post takeoff, the aircraft follows the infinite line sourced from the launch point in the direction of the takeoff waypoint
- takeoff waypoint altitude is used as a clearance altitude, set such that once above, the aircraft has cleared all ground occlusions and may proceed with the mission
- runway takeoff state machine simplified to throttle ramp, clamped to runway, climbout, and fly
- throttle ramp must complete before switching to next state to avoid a jump in throttle setpoint just after takeoff if the takeoff airspeed is reached before the ramp is complete
- roll constraints near ground post takeoff removed from runway takeoff class (handled externally now)
- minimum airspeed in TECS is reduced to takeoff speed (if necessary) to lower the underspeed detection bound
- lateral-directional guidance uses a different period parameter during ground roll
- apply constraint only for takeoff and landing modes
- add two params, wing span and wing height, to calculate a reasonable height at which roll limits can be opened
- takeoff situational knowledge removed from all other modes except manual (or actual takeoff mode)
- manual takeoff is marked complete if at a controllable airspeed
- minimum pitch bounds TECS until manual takeoff complete
- remove individual roll constraints during manual takeoff (ground proximity constraints coming in subsequent commit)
- underspeed condition only determined by true airspeed undershoot
- change binary underspeed condition to a continuous percent undersped
- ramp-in max throttle, pitch speed weight, and TAS setpoint reduction during underspeed to avoid jumpy commands at the true airspeed error boundary
- let true airspeed filter reach zero airspeed
- create integral and trajectory generator reset methods
- always run TECS unless in rotary-wing mode (or in transition)
- constantly reset TECS integrals and trajectory generators when landed
- simplify takeoff reset method
- removes _last_manual variable in favor of _skipping_takeoff_detection, which is handled in the control mode setter
- takeoff detection (both launch and runway) is skipped if entering takeoff mode from any other mode while having already been in the air
- added method to runway takeoff class for force setting the fly state when we want to skip the takeoff detection
* Change min > max notation to [min, max] in Parameters Markdown
* Update src/lib/parameters/px4params/markdownout.py
Co-authored-by: Thomas Stastny <thomas.stastny@auterion.com>
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
Co-authored-by: Thomas Stastny <thomas.stastny@auterion.com>
- array length of data was increased without changing the data type of
the variable holding the length
Signed-off-by: RomanBapst <bapstroman@gmail.com>
As they are always moving horizontally, the check doesn't make sense
for fixed-wings.
Also don't run the check while on ground to prevent getting a failed
check during pre-takeoff manipulation.
- trim throttle is handled entirely by the position controller
- navigator should use speed setpoints
- added flag gliding_enabled in position setpoint to stills support gliding
Signed-off-by: RomanBapst <bapstroman@gmail.com>
- allow compensation based on vehicle weight (parameterized)
- use density for calculating trim throttle compensation instead of pressure
- removed parameter FW_THR_ALT_SCL
Signed-off-by: RomanBapst <bapstroman@gmail.com>
Make Power Off tune not interruptable
This solves the case of Low Battery warning tune overriding the power
off tune, as now the Power off tune is not interruptable by any other
tune unless override flag is specified
commander_helper: resolve "redundant boolean literal in ternary expression result"
- Existing code was hard to read and quite ambiguous
- Also it allowed constantly re-sending the tune_control request for a
fixed duration tunes like "TUNE_ID_BATTERY_WARNING_SLOW", while not
respecting the tune duration
When wind is already estimated, we don't reset the states using airspeed
data, so it could be that the fusion fails if the airspeed isn't
consistent with the filter (test ratio > 1). In this case, don't start
the fusion.
When wind isn't already estimated, the wind states are reset using
airspeed so the fusion can start regardless of the current test ratio.
- As it is always only used for the vehicle command ack message
- It was a duplicate, hence making it error prone for maintainment
- The uORB message comments were updated to make the relationship with
the MAVLink message / enum definitions clear
split the fusion process into:
1. updateAirspeed: computes innov, innov_var, obs_var, ...
2. fuseAirspeed: uses data computed in 1. to generate K, H and fuse the
observation
from 300 ms to 60 seconds, to give enough time for the user to configure
the vehicle in the mean time.
This is needed especially when the battery cell count setting is wrong
(when it should be 3, but set to 4 for example), since then whenever you
boot the vehicle, it will shutdown after 300 ms, which leaves the user
puzzled as to exactly what's happening. And it also prevented the user
from changing the Parameter since it's shutting down so quickly.
60 second window is intended to be a reasonable time that will allow the
user to figure out what's going on (via checking the battery level on
QGC, etc) but also not deep discharge the battery to a dangerous level.
Fixes the error:
Aborting due to missing @type tag in file: 'build/px4_fmu-v5_test/etc/init.d/airframes/11001_hexa_cox'
This can happen due to a change to e.g. board_serial_ports, which changes
the CLI command and triggers a re-execution of the airframe processing.
- this allows landing gear to retract automatically when doing a takeoff
and the vehicle is considered high enough
Signed-off-by: RomanBapst <bapstroman@gmail.com>
- 4096 of 3 hex digits each for rev and ver is enough.
#defines used in SPI versions do not be long format, use use the macro
- Board provides a prefix and the formatting is sized and built in
- No need for funky board_get_base_eeprom_mtd_manifest interface
Original mft is used where the abstraction is done with the MFT interface
Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
If the capture GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these call can worst-case
starve flight critical processes leading to a loss of control. Since camera capture
is not flight critical, we now give up the capture
functionality and stop the interrupts to prevent the starvation of other processes.
If the PPS GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these calls can worst-case
starve flight critical processes leading to a loss of
control. Since PPS is not flight critical, we now give up the PPS
functionality and stop the interrupts to prevent the starvation of other processes.
Remove the entire external yaw handler, dynamic memory allocation,
pointer passing logic. Directly instanciate the weather vane instance
in the flight tasks that support it.
- remove internal accumulation and publish every valid raw sample synchronized with sensor
- store timestamp_sample from motion interrupt
- improve timing requirements from datasheet (minimum delays after register read/write)
- remove internal accumulation and publish every valid raw sample synchronized with sensor
- store timestamp_sample from motion interrupt
- improve timing requirements from datasheet (minimum delays after register read/write)
- all sources of optical flow publish sensor_optical_flow
- sensor_optical_flow is aggregated by the sensors module, aligned with integrated gyro, and published as vehicle_optical_flow
Co-authored-by: alexklimaj <alex@arkelectron.com>
Follow me : tidied second order filter implementation
Added velocity filtered info to uORB follow target status message, and rebase to potaito/new-follow-me-task
FollowMe : Rebasing and missing definition fixes on target position second order filter
Follow Me : Remove Alpha filter delay compensation code, since second order filter is used for pose filtering now
Followme : Remove unused target pose estimation update function
Follow Target : Added Target orientation estimation logic
Follow Target : Replaced offset vector based setpoint to rate controlled orbital angle control
Follow Target : Bug fixes and first working version of rate based control logic, still buggy
Follow Target : Added target orientation, follow angle, orbit angle value into follow_target_status uORB message for debugging
Follow Target : Fix orbit angle step calculation typo bug
Follow Target : Few more fixes
Follow Target : Few fixes and follow angle value logging bug fix
Follow Target : Added lowpass alpha filter for yaw setpoint filtering
Follow Target : Remove unused filter delay compensation param
Follow Target : Add Yaw setpoint filter initialization logic and bufix for when unwrap had an input of NAN angle value
Follow Target : Add Yaw setpoint filtering enabler parameter
Follow Target : Change Target Velocity Deadzone to 1.0 m/s, to accomodate walking speed of 1.5 m/s
Follow Target : Add Orbit Tangential Velocity calculation for velocity setpoint and logging uORB topics
Follow target : Fix indentation in yaw setpoint filtering logic
Follow Target : Fix Follow Target Estimator timeout logic bug that was making the 2nd order pose filter reset to raw value every loop
Follow Target : Remove debug printf statement for target pose filter reset check
Follow Target : Add pose filter natural frequency parameter for filter testing
Follow Target : Make target following side param selectable and add target pose filter natural frequency param description
Follow Target : Add Terrain following altitude mode and make 2D altitude mode keep altitude relative to the home position, instead of raw local position origin
Follow Target : Log follow target estimator & status at full rate for filter characteristics test
Follow Target : Implementing RC control user input for Follow Target control
Follow Target : edit to conform to updated unwrap_pi function
Follow Target : Make follow angle, distance and height RC command input configurable
Follow Target : Make Follow Target not interruptable by moving joystick in Commander
Follow Target : reconfigure yaw, pitch and roll for better user experience in RC adjusting configurations, and add angular rate limit taking target distance into account
Follow Target : Change RC channels used for adjustments and re-order header file for clarity
Follow Target : Fix Parameters custom parent macro, since using DEFINE_PARAMETERS alone misses the parameter updates of the parent class, FlightTask
Follow Target : Fix Orbit Tangential speed actually being angular rate bug, which was causing a phenomenon of drnoe getting 'dragged' towards the target velocity direction
Follow Target : Final tidying and refactoring for master merge - step 1
Add more comments on header file
Follow Target : tidy, remove unnecessary debug uORB elements from follow_target_status message
Follow Target : Turn off Yaw filtering by default
Follow Target : Tidy maximum orbital velocity calculation
Follow Target : add yaw setpoint filter time constant parameter for testing and fix NAV_FT_HT title
Follow Target : Add RC adjustment window logic to prevent drone not catching up the change of follow target parameters
Follow Target : fixes
Follow Target: PR tidy few edits remove, and update comments
Follow Target : apply comments and reviews
Follow Target : Edit according to review comments part 2
Follow Target : Split RC adjustment code and other refactors
- Splitted the RC adjustment into follow angle, height and distance
- Added Parameter change detection to reset the follow properties
- Added comments and removed yaw setpoint filter enabler logic
Follow Target : Modify orbit angle error bufferzone bug that was causing excessive velocity setpoints when setpoint catched up with raw orbit setpoint
Follow Target : Remove buffer zone velocity ramp down logic and add acceleration and rate limited Trajectory generation library for orbit angle and velocity setpoint
Follow Target : Remove internally tracked data from local scope function's parameters to simplify code
Follow Target : Fix to track unwrapped orbit angle, with no wrapping
Follow Target : Apply user adjustment deadzone to reduce sensitivity
Follow Target : Apply suggestions from PR review round 2 by @potaito
Revert submodule update changes, fall back to potaito/new-followme-task
Follow Target : [Debug] Expose max vel and acceleration settings as parameters, instead of using Multicopter Position Controller
's settings
Follow Target : Use matrix::isEqualF() function to compare floats
Follow Target : Add Acceleration feedback enabler parameter and Velocity ramp in initial commit for overshoot phenomenon improvement
Follow Target : Implement Velocity feed forward limit and debug logging values
Follow Target : Apply Velocity Ramp-in for Acceleration as well & Apply it to total velocity setpoint and not just orbit tangential velocity component
Follow Target : Don't set Acceleration setpoint if not commanded
Follow Target : Use Jerk limited orbit angle control. Add orbit angle tracking related uORB values"
Follow Target : Add Orbit Angle Setpoint Rate Tracking filter, to take into consideration for calculating velocity setpoint for trajectory generator for orbit angle
Revert "Follow Target : Add Orbit Angle Setpoint Rate Tracking filter, to take into consideration for calculating velocity setpoint for trajectory generator for orbit angle"
This reverts commit a3f48ac7652adb70baf3a2fed3ea34d77cbd6a70.
Follow Target : Take Unfiltered target velocity into acount for target course calculation to fix overshoot orbit angle 180 deg flip problem
Follow Target : Remove Yaw Filter since it doesn't make a big difference in yaw jitterness
Follow Target : Remove velocity ramp in control & remove debug values from follow_target_status.msg
Follow Target : Tidy Follow Target Status message logging code
Follow Target : Remove jerk and acceleration settings from Follow Target orbit trajectory generation
Follow Target : Change PublicationMulti into Publication, since topics published are single instances
Follow Target : Edit comments to reflect changes in the final revision of Follow Target
Follow Target : Apply incorrectly merged conflicts during rebase & update Sticks function usage for getThrottled()
Follow Target : Apply final review comments before merge into Alessandro's PR
Apply further changes from the PR review, like units
Use RC Sticks' Expo() function for user adjustments to decrease sensitivity around the center (0 value)
Update Function styles to lowerCamelCase
And make functions const & return the params, rather than modifying them
internally via pointer / reference
Specify kFollowPerspective enum as uint8_t, so that it can't be set to negative value when converted from the parameter 'FLW_TGT_FP'
Fix bug in updateParams() to reset internally tracked params if they actually changed.
Remove unnecessary comments
Fix format of the Follow Target code
Fix Follow Perspective Param metadata
follow-me: use new trajectory_setpoint msg
Convert FollowPerspective enum into a Follow Angle float value
1. Increases flexibility in user's side, to set any arbitrary follow
angle [deg]
2. Removes the need to have a dedicated Enum, which can be a hassle to
make it match MAVSDK's side
3. A step in the direction of adding a proper Follow Mode (Perspective)
mode support, where we can support kite mode (drone behaves as if it is
hovering & getting dragged by the target with a leash) or a constant
orbit angle mode (Drone always on the East / North / etc. side, for
cinematic shots)
Continue fixing Follow Target MAVSDK code to match MAVSDK changes
- Support Follow Angle configuration instead of Follow Direction
- Change follow position tolerance logic to use the follow angle
*Still work in progress!
Update Follow Me MAVSDK Test Code to match MAVSDK v2 spec
- Add RC Adjustment Test case
- Change follow direction logic to follow angle based logic completely
- Cleanup on variable names and comment on code
follow-me: disable SITL test
Need to update MAVSDK with the following PR:
https://github.com/mavlink/MAVSDK/pull/1770
SITL is failing now because the follow-me
perspectives are no longer defined the
same way in MAVSDK and in the flight task.
update copyright year
follow-me: mark uORB topics optional
Apply review comments
more copyright years
follow-me sitl test: simpler "state machine"
flight_mode_manager: exclude AutoFollowTarget and Orbit on flash contrained boards
Remove unnecessary follow_target_status message properties
- As it eats up FLASH and consumes uLog bandwidth
rename follow_me_status to follow_target_status
enable follow_target_estimator on skynode
implement the responsiveness parameter:
The responsiveness parameter should behave similarly to the previous
follow-me implementation in navigator. The difference here is that
there are now two separate gains for position and velocity fusion.
The previous implemenation in navigator had no velocity fusion.
Allow follow-me to be flown without RC
SITL tests for follow-me flight task
This includes:
- Testing the setting for the follow-me angle
- Testing that streaming position only or position
and velocity measurements both work
- Testing that RC override works
Most of these tests are done with a simulated model
of a point object that moves on a straight line. So
nothing too spectacular. But it makes the test checks
much easier.
Since the estimator for the target actually checks new
measurements and compares them to old ones, I also added
random gausian noise to the measurements with a fixed seed
for deterministic randomness. So repeated runs produce
exactly the same results over and over.
Half of the angles are still missing in MAVSDK. Need to create
an upstream PR to add center left/right and rear left/right options.
These and the corresponding SITL tests need to be implemented
later.
sitl: Increase position tolerance during follow-me
Astro seems to barely exceed the current tolerance (4.3 !< 4.0)
causing CI to fail. The point of the CI test is not to check
the accuracy of the flight behaviour, but only the fact that the
drone is doing the expected thing. So the exact value of this
tolerance is not really important.
follow-me: gimbal control in follow-me
follow-me: create sub-routines in flight task class
follow-me: use ground-dist for emergency ascent
dist_bottom is only defined when a ground facing distance sensor exist.
It's therefore better to use dist_ground instead, which has the distance
to the home altitude if no distance sensor is available.
As a consequence it will only be possible to use follow-me in a valley
when the drone has a distance sensor.
follow-me: point gimbal to the ground in 2D mode
follow-me: another fuzzy msg handling for the estimator
follow-me: bugfix in acceleration saturation limit
follow-me: parameter for filter delay compensation
mantis: dont use flow for terrain estimation
follow-me: default responsiveness 0.5 -> 0.1
0.5 is way too jerky in real and simulated tests.
flight_task: clarify comments for bottom distance
follow-me: minor comment improvement
follow-me: [debug] log emergency_ascent
follow-me: [debug] log gimbal pitch
follow-me: [debug] status values for follow-me estimator
follow-me: setting for gimbal tracking mode
follow-me: release gimbal control at destruction
mavsdk: cosmetics 💄
Symmetric buffers allow a much more reliable QGC Wifi telemetry connection especially when (virtual) joysticks are used. (this board does not provide RX DMA on UART 4 as its timer does DSHOT).
The noise spectral density, NSD, (square root of power spectral density) is a
continuous-time parameter that makes the tuning independent from the EKF
prediction rate.
NSD corresponds to the rate at which the state uncertainty increases
when no measurements are fused into the filter.
Given that the current prediction rate of EKF2 is 100Hz, the
same tuning is obtained by dividing the std_dev legacy parameter by 10:
nsd = sqrt(std_dev^2 / 100Hz)
The noise spectral density, NSD, (square root of power spectral density) is a
continuous-time parameter that makes the tuning independent from the EKF
prediction rate.
NSD corresponds to the rate at which the state uncertainty increases
when no measurements are fused into the filter.
Given that the current prediction rate of the wind estimator is 1Hz, the
same tuning is obtained with the same values as before.
1. Rename *_header_s structs to *_s, since the _header postfix is not
helpful
2. Rename the "key" string variables in the message structs to
"key_value_str" as the string actually contains not just the key but the
key and value pair information
3. Add comments on other uLog messages to clarify use (need more
improvement / can be even more simplified)
* sih: Move sih out of work queue
This reverts commit bb7dd0cf00.
* sih-sim: Enable sih in sitl, together with lockstep
* sih-sim: new files for sih: quadx and airplane
* sih: Added tailsitter for sih-sitl simulation
* sitl_target: Added seperate target loop for sih
* jmavsim_run: Allow jmavsim to run in UDP mode
* lockstep: Post semaphore on last lockstep component removed
* sih-sim: Added display for effectively achieved speed
* sih: increase stack size
* sih-sim: Improved sleep time computation, fixes bug of running too fast
* sitl_target: place omnicopter in alphabethic order
Co-authored-by: romain-chiap <romain.chiap@gmail.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- documentation of units, params, returns, and descriptions for variables and methods
- rename ambiguous or erroneous state variables
- remove unused or unecessary input arguments to functions
- remove ugly header white space
The safetyButtonHandler() reports that the safety statatus
changed on the first loop iteration when safety is disabled which makes
sense to inform the system that safety is off but the tune for the user
should not be played because it interrupts the startup tune.
They cause problems with building px4_msgs in ROS2 Humble Hawksbill and removing them fixes the issue.
Co-authored-by: Agata Barcis <agata.barcis@tii.ae>
This corrects the board definition to use the proper polarity
for the brick power valid signal, thus allowing the board to
detect the battery and monitor it properly.
internal PX4IO safety_off state is removed and replaced with a normal safety button event. From this 'commit' commander is taking care of the PX4IO safety.
- mavlink in PX4/Firmware (56106be4805cb2f70d22ad31b87fbd9774f0d0f3): 99e82cad70
- mavlink current upstream: 0909631552
- Changes: 99e82cad70...0909631552
09096315 2022-05-26 Hamish Willee - Clarify and cross reference home position everywhere (#1836)
38c1a99f 2022-05-25 Julian Oes - WIND_COV: clarify description and unknown value (#1845)
- on common IMUs like the mpu6000, mpu9250, icm20602, etc each FIFO
sample is only 12 bytes so this is still more than large enough for the
worst case transfer
- free memory is getting tight on these older boards (depending on
configuratoin) and the pixhawk 2 cube still has 2 other superior IMUs, so this is just
dropping dead weight
H7 Only supports 2 not 3 CAN interfaces.
CanInitHelper passes in in the run time configuration of
the number of interfaces. The code was ignoring these!
This type (23) doesn't specify a motor number, so it can't be properly handled.
There are duo (19) and quad (20) tailsitter types that still work in simulation.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Based on feedback that very often the battery is used down too low.
I observed this happens consistently when the cell voltage is properly
load compensated. The default load compensation before #19429 was very
inaccurate and resulted in unpredictable estimate.
After that if there is a usable current measurement and the battery is
within expected tolerances of the default internal resistance the
compensation is pretty good and 3.5V is too low for an empty compensated
cell voltage. That was seen in various logs where the compensated
cell voltage was already dropping fast after 3.6V.
In case the voltage is not load compensated the vehicle estimates the
state of charge a bit too low which is safer than to high
especially for a default configuration.
internal PX4IO safety_off state is removed and replaced with a normal safety button event. From this 'commit' commander is taking care of the PX4IO safety.
Without this, uavcan creates MixingOutput classes which then create
empty actuator_outputs publications. This then prevents the motor
output in HITL to be forwarded to the simulator via mavlink.
The baro observation noise parameter is often over-estimated in order as
a measure to mitigate temporary offsets in the readings due to wind
gusts or poor pressure compensation tuning. The side effect is that the
innovation sequence monitoring based on normalized innovation struggles
to detect an offset in the state because the innovation isn't
statistically significant.
To counter this issue, a simpler check is added to trigger the process
noise boost when the innovation has the same sign for a long period of
time.
- sitl_gazebo in PX4/Firmware (422be90140): 48440d7b5c
- sitl_gazebo current upstream: 5eb5df8045
- Changes: 48440d7b5c...5eb5df8045
5eb5df8 2022-04-28 stmoon - ROS2_PLUGIN set OFF by default
c8f4d5b 2022-04-28 stmoon - update the motor failure plugin for ros2
1. Change the paragraph headings to proper Markdown headings (easier to
link / structure the Markdown)
2. Move PULL_REQUEST_TEMPLATE into .github folder
3. Change description in Issue template and remove outdated DevGuide
Repository information
4. Add a bug emoji to bug report isue template
5. Support automatically adding labels 'bug-report' and
'feature-request' to easily sort / filter appropriate issues in Github
We use lockdown to prevent outputs like motors and servos from being
active in HITL simulation. This means that we can't treat the lockdown
flag as a flight_terminated, otherwise we can't arm in HITL at all.
I got multiple times the feedback now that a consistent delay
is helpful and makes sense but the default delay
is too long
for low battery action where you're trying to come back in time
and possibly the emergency reaction kicks in while the critical action
is executing which leads to a longer accumulated delay.
- mavlink in PX4/Firmware (87c73145b36a835b1635de0498a5613a7af5cafc): a1cb2c0e71
- mavlink current upstream: 99e82cad70
- Changes: a1cb2c0e71...99e82cad70
99e82cad 2022-05-19 Hamish Willee - Deprecated GPS_INJECT_DATA (#1842)
bf3df03d 2022-05-16 Hamish Willee - WIND_COV - accuracy units are m/s (#1844)
a73d4864 2022-05-11 Hamish Willee - development.xml FIGURE_EIGHT_EXECUTION_STATUS - add a note about it being set at lower rate (#1841)
To return Exponential Values, which is helpful for reducing the
sensitivity of the stick around the centered value (0), since it's
exponential curve.
Useful for user adjustment implementations, where accidentally touching the stick
wouldn't have so much effect when using the Exponential value, compared
to using the raw position value.
This fixes an invalid memory access when exiting the module:
exit_and_cleanup destroys the object, but lock_guard is destructed after
and accesses the lock.
- limit to handling only 1 motor failure
- Log which motor failures are handled
- Remove motor from effectiveness matrix without
recomputing the scale / normalization
- this allows jumping straight to a non-SBUS RC protocol
- increased the scan time per protocol 300->500 ms, which the newer DSM parser seems to need in some cases.
- only set RC_INPUT_PROTO if we've had a successful RC lock for > 3 seconds
Normally _should_run for mission is only ever true if _should_run for the
normal log is. There are exceptions though:
- the log buffer fails to allocate
- there was a write failure (e.g. due to SD card removal)
In that situation, the writer would not wait anymore but busy-loop.
This replaces the propeller_torque_disabled flag to disable yaw by differential thrust
for tiltrotor and tailsitter VTOLs, as propeller_torque_disabled is not enough to set
effectiveness of an acutator in the yaw axis to 0 in case it's tilted.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Special case tiltrotor: instead of passing a 3D thrust vector (that would mostly have a x-component in FW, and z in
MC), pass the vector magnitude as z-component, plus the collective tilt. Passing 3D thrust plus tilt is not feasible as they
can't be allocated independently, and with the current controller it's not possible to have collective tilt calculated
by the allocator directly.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
The flight termination action on geofence violation is described as only trigger, when the corresponding circuit breaker is not disabled. However, the description of the circuit breaker states, that the geofence action is not depedning on this circuit breaker. The implementation follows the description of the circuit breaker. Hence the GF_ACTION description is adapted.
- add logic for detecting high wind speed in Commander,
and handle it toghether with wind speed warning
- trigger and enforce RTL if COM_WIND_MAX is breached
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Adds COM_FLT_TIME_MAX param and logic in Commander to enforce RTL when
flight time is above this value. User can only override to LAND mode,
but not proceed flight beyond that.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
If both local position and altitude were not valid, then both RC loss and
datalink loss would not trigger any failsafe at all, independently from
the configured action.
Calculating K(HP) takes less operations than (KH)P because K and H are
vectors.
Without considering the sparsity optimization:
- KH (24*24 operations) is then a 24x24 matrix an it takes
24^3 operations to multiply it with P. Total: 14400 op
- HP (24*(24+24-1) operations) is a row vector
and it takes 24 operations to left-multiply it by K. Total:1152 op
This is a combination of the originally introduced delay:
06c10f61c1
then the emergency failsafe being changed to not just land,
position control being rescheduled to not overwrite every setpoint in:
e502214429576ce68ac3fee9d2db19112f4604b9
and it being fixed by overwriting the setpoint but not removing
the long obsolete hystersis here:
114e85d260
- remove separate flaperon controls input to mixer instead enable spoiler support
- add slew rate limiting on both flap and spoiler controls
- add spoiler configuration for Landing and Descend
- add trimming from spoiler deflection
- FW Attitude control: remove FW_FLAPS_SCL param -->
The flap settings for takeoff and landing are now specified relative to full range.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
[4] is reserved for Flaps, so also having the tilt on it was preventing us from
using flaps on tiltrotors, and other ripple effects.
By using [8] the tilt is separated from all other channels - it requires to increase the size of
actuator_controls by 1 to 9.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
There was a time window where if a task with higher priority than the main
logger thread would busy-loop, it would block both logging threads and the
watchdog would not trigger if the writer was in idle state.
This can happen for fast SD card writes.
when the vertical pos or vel innov ratio is above the threshold, the
other one needs to be significant too and not just positive to trigger
the failure
- on some H7 boards (cuav x7pro tested) there's an occasional hard fault when starting the mavlink shell that is no longer reproducible with the slightly expanded locking
- this is likely just changing the timing (holding the sched lock for longer), but this should be harmless for now until we can identify the root cause
Weather vane should only set a yawrate setpoint, but no yaw setpoint.
Setting it to NAN when WV is active makes sure that whatever _yaw_setpoint
is set previously (e.g. through Waypoint) is not used.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- set local home using global pos and global home
- set local home using GNSS pos and global home
- set global home using global ref of local frame and local home
This is to make clear that the relevant part of the home position
message for navigator is the global one. Local home position isn't
required as everything is done in global coordinates.
The specific home_alt_valid is used when lat/lon are not used
- always try to set local or global home position when possible
- set global home with GNSS position if global pos from EKF isn't
available
- reset home when significantly moved from home before takeoff (checking
lpos or gpos or GNSS)
- reset home on takeoff transition
- reset home on mavlink arm command
- remove "home required accuracy" parameters, rely on validity flags
- fixes the deadlock in px4io ioctl mixer reset
- px4io Run() locks (CDev semaphore)
- mixer load goes through px4io ioctl MIXERIOCRESET which calls MixingOutput::resetMixerThreadSafe()
- MixingOutput::resetMixerThreadSafe() stores a Command::Type::resetMixer command in an atomic variable, schedules a work queue cycle, then sleep spins until the command is cleared
- the execution of the cycle eventually calls back into PX4IO::updateOutputs(), which tries to lock (and waits forever)
- most px4_io-v2 boards have a blue LED that breathes for status
- the pixhawk 2.1 (hex) re-used this blue LED for as an IMU heater (active low), but kept the same board id (so we have to detect at runtime)
- the new cubepilot boards (yellow, orange) inverted the polarity of this heater pin
- untangle the mess slightly so that things we know statically (eg cubepilot cubeorange LEDs and heater polarity) are handled at build time.
To pass from invalid to valid:
- time hysteresis
- some vertical velocity
- test ratio < 1
- low-passed signed test ratio < 1
To pass from valid to invalid:
- low-passed signed test ratio >= 1
At each new valid range measurement, the time derivative of the distance
to the ground is computed and compared with the estimated velocity.
The average of a normalized innovation squared statistic check is used
to detect a bias in the derivative of distance measurement,
indicating that the distance measurements are kinematically inconsistent
with the filter.
- mavlink in PX4/Firmware (a1530591764f0c694560e4bb6ae41c15d3e35c9b): 0133e5db7f
- mavlink current upstream: 56a5110d38
- Changes: 0133e5db7f...56a5110d38
56a5110d 2022-04-09 Tom Pittenger - Add radius to DO_REPOSITION (#1825)
3b5959bd 2022-04-07 Thomas Debrunner - Option to not reset non-configurable params in preflight storage (#1826)
For many VTOLs/fixed-wing drones a 50m loiter radius is too tight, and
going to 80m is a better and safer default.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- In this case, no action is configured for datalink lost. Action is configured for RC lost.
- In case of no data link and no rc failsafe is enabled but reporting a "no_datalink" reason but "no_rc_and_no_datalink" seems more explicit.
- previously an invalid decode would continue to be transferred to the FMU (at 50 Hz) and published to the rest of the system as successfully decoded new RC data
- by only publishing new successful decodes we can more effectively discard invalid data in downstream consumers
PX4 supports int32 parameter types by interpreting the 32 bits in
the float field as an int32 field. To signal this behaviour, it should
set the bit which is described as PARAM_ENCODE_BYTEWISE.
PX4 had always handled parameters this way but never actually sent the
capability (which back then was called PARAM_UNION), however, it should
have. This came up recently in the MAVLink devcall when these flags were
discussed. The takeaway was to remove the flags to make it clearer and
to make sure the projects (like PX4) send them out correctly.
mathlib: add second order reference model filter with optional rate feedback (#19246)
Reference models can be used as filters which exhibit a particular, chosen (reference) dynamic behavior. This PR implements a simple second order transfer function which can be used as such a reference model, additionally with rate feedback. The system is parameterized by explicitly set natural frequency and damping ratio. Another nice externality is that the output state and rate are kinematically consistent. Forward-euler and bilinear transform discretizations for the state space integration step are available.
- introduce BAT_AVRG_CURRENT param that is used for init of average current estimate
- increase filtering of average current estimation
- only update average current filter when armed
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This fixes unspecified behaviour due to evaluation order of args.
It's up to the compiler whether next_number() or next_dots() is executed
first which means that the behaviour is not properly specified.
- sensor_baro.msg use SI (pressure in Pascals)
- update all barometer drivers to publish directly and remove PX4Barometer helper
- introduce baro cal (offset) mainly as a mechanism to adjust
relative priority
- commander: add simple baro cal that sets baro offsets to align with
GPS altitude (if available)
- create new sensors_status.msg to generalize sensor reporting
- things like arming requests can be dependent on current nav state
that might requested by a previous command, but the state machine
transition will only happen after command processing
New parameter for actions after a quadchute (COM_QC_ACT)
Co-authored-by: Jonas <jonas.perolini@rigi.tech>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
- new static notch filter configured via IMU_GYRO_NF1_FRQ and IMU_GYRO_NF1_BW
- existing notch parameters IMU_GYRO_NF_FREQ and IMU_GYRO_NF_BW become
IMU_GYRO_NF0_FRQ and IMU_GYRO_NF0_BW
- when estimating the peak frequency the magnitude of side buckets will
be factored in, so it doesn't make sense to potentially treat them as
separatey detected peaks
- set MAV_TYPE as a parameter default per vehicle type, or airframe if necessary
- cleanup MAV_TYPE param metadata and commander helper to only include
what's currently used in PX4
It accesses kernel internal structures directly; this needs to be
worked out with some proper userspace-kernel interface
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This is needed for DMA capable memory for fat also in the user side;
the file system doesn't seem to work reliably without.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
For protected/kernel builds the cxx static initializations
needs to be done also in kernel side, since px4 creates
c++ objects in kernel
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Implement an interface for protected build to access parameters.
The implementation only does IOCTL calls to the kernel, where the parameters
live.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Put all functions which are commont to flat build and protected kernel and
userspace to an own source file
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- the estimated mag bias was requiring > 30 seconds of continuous 3d
mag fusion to be reported stable (and saved back to mag cal), this
restores the original intent requiring 30 seconds of accumulated valid
3d mag fusion
Need to log both, because on some systems the
information will come in directly as a
landing_target_pose message, and on others
it's coming in as irlock_report and then filtered
in PX4 to produce the landing_target_pose message.
- this was an experiment to casually monitor sensor offsets relative to temperature, but now that all calibration offsets can be adjusted post-flight the stored temperature can be misleading
- deleting to save a little bit of flash (and storing the temperature wasn't useful)
Otherwise the setpoint from weather vane is constantly overwritten by it,
even if the yaw stick is not moved.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
about: See https://github.com/PX4/Devguide for documentation issues
about: See https://github.com/PX4/px4_user_guide for documentation issues
---
PX4 has dedicated repositories for developer documentation (https://github.com/PX4/Devguide) and user documentation (https://github.com/PX4/px4_user_guide).
## Attention! Please read the note below
**Please submit the documentation issue to the [User Guide](https://github.com/PX4/px4_user_guide) repository.**
Please use [PX4 Discuss](http://discuss.px4.io/) or [Slack](http://slack.px4.io/) to align on pull requests if necessary. You can then open draft pull requests to get early feedback.
**Describe problem solved by this pull request**
A clear and concise description of the problem this proposed change will solve.
## Describe problem solved by this pull request
A clear and concise description of the problem this proposed change will solve. Or, what it will improve.
E.g. For this use case I ran into...
**Describe your solution**
## Describe your solution
A clear and concise description of what you have implemented.
**Describe possible alternatives**
## Describe possible alternatives
A clear and concise description of alternative solutions or features you've considered.
**Test data / coverage**
## Test data / coverage
How was it tested? What cases were covered? Logs uploaded to https://review.px4.io/ and screenshots of the important plot parts.
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/master/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
PX4 is highly portable, OS-independent and supports Linux, NuttX and MacOS out of the box.
* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/PX4-Autopilot/blob/master/LICENSE))
## Building a PX4 based drone, rover, boat or robot
The [PX4 User Guide](https://docs.px4.io/master/en/) explains how to assemble [supported vehicles](https://docs.px4.io/master/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/master/en/#support) if you need help!
The [PX4 User Guide](https://docs.px4.io/main/en/) explains how to assemble [supported vehicles](https://docs.px4.io/main/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
## Changing code and contributing
This [Developer Guide](https://docs.px4.io/master/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
This [Developer Guide](https://docs.px4.io/main/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
Developers should read the [Guide for Contributions](https://docs.px4.io/master/en/contribute/).
See the [forum and chat](https://dev.px4.io/master/en/#support) if you need help!
Developers should read the [Guide for Contributions](https://docs.px4.io/main/en/contribute/).
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
### Weekly Dev Call
The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/master/en/contribute/#dev_call).
The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/contribute/).
> **Note** The dev call is open to all interested developers (not just the core dev team). This is a great opportunity to meet the team and contribute to the ongoing development of the platform. It includes a QA session for newcomers. All regular calls are listed in the [Dronecode calendar](https://www.dronecode.org/calendar/).
@ -88,35 +88,43 @@ This repository contains code supporting Pixhawk standard boards (best supported
@@ -88,35 +88,43 @@ This repository contains code supporting Pixhawk standard boards (best supported
* FMUv6X and FMUv6U (STM32H7, 2021)
* Various vendors will provide FMUv6X and FMUv6U based designs Q3/2021
* [Raspberry PI with Navio 2](https://docs.px4.io/main/en/flight_controller/raspberry_pi_navio2.html)
Additional information about supported hardware can be found in [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/master/en/flight_controller/).
Additional information about supported hardware can be found in [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
## Project Roadmap
A high level project roadmap is available [here](https://github.com/orgs/PX4/projects/25).
## Project Governance
The PX4 Autopilot project including all of its trademarks is hosted under [Dronecode](https://www.dronecode.org/), part of the Linux Foundation.
<ahref="https://www.linuxfoundation.org/projects"style="padding:20px;"><imgsrc="https://mavlink.io/assets/site/logo_linux_foundation.png"alt="Linux Foundation Logo"width="80px"/></a>