- 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"
- 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>
- 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>
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 💄
* 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>
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.
- 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>
- 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
This changes the way RC is handled for the Mantis:
- The RC values are re-written when arriving over MAVLink. They are
rescaled from 0..4095 to 1000..2000 and the channel bits added to
separate channels. This makes the downstream handling easier.
- Gimbal pitch is moved from Aux1 to Aux2 as that should be the default.
- Aux3 and Aux4 are used for the photo and video trigger.
- The speed button is used as the FLTMODE channel and set to switch
between POSCTL and ALTCTL.
The limits might somewhat match the sensor, guessed based on the
original driver.
The quality is set so that spikes when sitting on the ground are not
used.
- uavcan firmware server no longer shuts down when arming (nodes might restart in flight)
- always handle UAVCAN parameters with or without the FW server active
- remove legacy ESC enumeration in FW server
- allow effectiveness matrix to select control allocator method
(desaturation algorithm)
- add actuator_servos publication
- add support for multiple matrices (for vtol)
- add updateSetpoint callback method to actuator effectiveness to allow it
to manipulate the actuator setpoint after allocation
- handle motor stopping & reversal
- add control surfaces & tilt servos
- handle standard vtol + tiltrotor
- rename MC rotors params & class to be more generically usable
- fixes and enables ActuatorEffectivenessRotorsTest
This fixes a case where the px4 startup is not stopped when the
px4 process is killled using -SIGKILL against the px4 deamon.
In that case, the currently executing command/client is killed
and properly shutting down with result -1, however, the next command
is started anyway.
This means that the next time we try to run the simulation we get a
"PX4 daemon already running for instance 0" error and PX4 doesn't start
properly.
By adding exit on error, we properly exit in the case where the startup
script gets stopped/killed.
- cmake NuttX build wrapper compile in place instead of copying source tree to build directory
- slightly faster skipping necessary copying (depending on system)
- allows debugging in place
- easier to work directly in NuttX following official documentation
- simplifies overall build which should make it easier to resolve any remaining NuttX dependency issues in the build system
- the downside is switching back and forth between different builds always require rebuilding NuttX, but I think this is worth the improved developer experience
- also no longer builds px4io and bootloader in every single build, for most users these rarely change and we're wasting a lot of build time
Remove params from airframe configs that are just set again
to the param default value or to the value that is
specified in the mc_default, fw_default or vtol_default.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- no longer start sercon or mavlink usb by default
- on USB connection (VBUS) monitor serial USB at low rate and start Mavlink if there's a HEARTBEAT or nshterm on 3 consecutive carriage returns
- the mavlink USB instance is automatically stopped and serdis executed if USB is disconnected
- skipping Mavlink USB (and sercon) saves a considerable amount of memory on older boards
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>
based on our experience with VTOL it makes sense to change the yaw mode default. You always want your VTOL to yaw in transition direction before starting the transition.
- include icm20948 on most boards by default
- create more test variants for default boards near flash limit (cuav_nora_test, cuav_x7pro_test, holybro_durandal-v1_test)
I don't think we should be broadcasting by default as we haven't done
that in the past. This suddenly spams the network with a lot of
messages, and leads to confusing situations in offices where there are
multiple PX4 SITL and QGC intances are open.
PX4 uses banks of 8 outputs as a logical structure. Boards that have
more outputs than 8 get multiple instances. This is an arbitrary choice
that helps with overall structure and enables the mixing of different
device classes (like FMU, IO or UAVCAN).
These changes remove the two code paths to updates (forceupdate and update) and try to reboot and bootload IO independent of its state, wether it is in bootloader mode already, safety switch is off or if it is in "nominal state" (running and safety on). This ensures that there are no conditions where user error or boot sequence can prevent a successful upgrade. The only state where an upgrade will not be done is if the system is fully armed.
Previously, we did not set a remote port which meant that the default
remote port 14550 was used. This meant that the mavlink instance
talking to the gimbal was interfering with the connection to the ground
station (on 14550).
This is a hack to make sure the messages from the gimbal arrive at other
links (e.g. the ground station). It means that the gimbal does not get
flooded with all other messages that would get forwarded but messages
from the gimbal will still make it through.
* Commit for the Integration of a position controller for the a Underwater vehicle.
This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw.
Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0.
Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction.
In general the idea is to have this position module to control the position of the uuv. The position module reseives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module.
Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw).
* Commit for the Integration of a position controller for the a Underwater vehicle.
This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw.
Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0.
Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction.
In general the idea is to have this position module to control the position of the uuv. The position module receives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module.
Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw).
Currently not solved/missing:
- Problem with gazebo model(propeller moving chaotically).
- Mixer correct gazebo vs real life (has to be tested in the future)
- correct integration in uuv.apps (when choose which module)
- very basic controller chosen (could be improved a lot in the future)
* Remove error caused by unused variables and a different build error
* added better description of the parameter. Additionally the group is changed.
* added better description of the parameter. Additionally the group is changed.
Fixed bug about parameter
* Added EOF to the files.
* Removed parameter for direct position control for safety reasons.
* small bugfix
This commit moves the steering output from yaw to the roll channel to better reflect the lateral control input / reaction mapping. It also removes old unused parameters and modernizes the mainloop to remove unnecessary polling.