* Enable motor controls for fixed wing mode in tailsitters
This commit enable motor controls in fixed wing mode for tailsitters
This is needed for enabling quad tailsitters
* VTOL: differential thrust in FW: adapt params to be generic for all axes
Until now only suppoted on yaw axis. Not to be supported also on Roll and Pitch.
- VT_FW_DIFTHR_EN: make bitmask for all three axes independently. First bit is Yaw,
sucht that existing meaning of VT_FW_DIFTHR_EN doesn't change.
- VT_FW_DIFTHR_SC: rename to VT_FW_DIFTHR_S_Y and add same params for roll (_R) and
pitch (_P).
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
* Integrate differential control bits to three axis control
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- update all msgs to be directly compatible with ROS2
- microdds_client improvements
- timesync
- reduced code size
- add to most default builds if we can afford it
- lots of other little changes
- purge fastrtps (I tried to save this multiple times, but kept hitting roadblocks)
* Changed sitl_gazebo to the advanced liftdrag plugin fork.
* Added advanced plane and its associated parameters to PX4. Also tweaked one of the plugins to fix a compilation error (upcasting from float to double).
* Switched gazebo back to main branch, to avoid merge conflicts.
* Change simulator bridge back to what it was in main branch
* Changed sitl_gazebo to match the PX4 main branch's (commit hash b968405)
* Changed SimulatorIgnitionBridge to match most recent main.
- for convenience merge px4_sitl_ign into px4_sitl_default, but allow simulator_ignition_bridge to quietly skip inclusion if ignition-transport isn't available
- simulator_ignition_bridge only try setting the system clock in
lockstep builds
- this simplifies usage and CI system dependencies
- rcS parameter backup try to directly restore param (FRAM) from backup (in case SD card is removed before successful export)
- rcS parameter backup logging rearrange to capture more logging output (param_import_fail.txt)
- posix rcS try to keep param backup and restore roughly in sync with NuttX rcS
- tinybson fix debug printf format
- param_export_internal ensure file descriptor positioned at 0 (precaution)
This feature allows user to use a Gripper type pacakge delivery
mechanism on a drone to trigger the delivery during a mission via the
mission item `DO_GRIPPER`.
This is a minimal change that is intended to have simplest pacakge
delivery feature on PX4, however the future scope would extend this
feature out of Navigator, and rather move towards a federated PX4
(flight-mode flexibility) architecture. But until then, this will serve
the purpose.
Update Tools/sitl_gazebo submodule to remove sdf file overwrite error
- There was an error happening due to .sdf file being overwritten, it
was caused by a wrongfully added. sdf file.
- This update pulls in the PR commit: https://github.com/Auterion/sitl_gazebo/pull/147
Initial cut on supporing PAYLOAD_PLACE mission item
Tidy and comment on navigation.h to clarify mission item definition
- Convert vehicle command ack subscription data type to
SubscriptionData, to not care about having a dedicated struct for
copying the latest data
- Tidy and comment on navigation.h to clarify the definition of
mission_item_s, which is confusing as it is an intergration of MAVLink
Standard into PX4's internal Mission Item structure
Rename mission_block's mission item reached function & cleanup navigator
- Isolated Handle Vehicle Commands function inside the Navigator
- Rename mission_block's mission item reached function to 'reached or
completed', as the navigation command can also be an action (e.g.
DO_SET_SERVO, which doesn't make sense to refer to as 'reached' when we
have successfully done executed the command)
Include MAVLink PR commit to include payload_drop message
More changes to add payload_drop MAVLink message support
- Comitting for testing purposes
Add mission item payload_drop to vehicle command payload drop link
- Now with a mission item with the nav_cmd set to 'payload drop', the
appropriate 'payload drop' vehicle command will be issued
Make Payload drop executable via Mission Plan
Implement payload_drop module to simulate payload delivery
- Simple module that acknowledges the payload drop vehicle command after
certain time, to simulate a successful delivery
Additional changes - payload drop module not working yet
- Need to do more thread stuff to make it work :(
Fix Payload Drop enum mismatch in vehicle_command enums
- First functional Payload Drop Implementation MVP
- Simple Ack & resuming mission from Navigator tested successfully
Hold the position while executing payload drop mission item
- Still the position hold is not solid, maybe I am missing something in
the position setpoint part and all the internal implications of
Navigator :(
Add DO_WINCH command support
Some fixes after rebase on develop branch
- Some missed brackets
- Some comment edits, etc
Add DO_WINCH command support
- Still has a problem of flying away from the waypoint while the
DO_WINCH is being executed, probably position setpoint related stuff :(
Apply braking of the vehicle for DO_WINCH command
- Copies the behavior of NAV_CMD_DELAY, which executes a smooth, braking
behavior when executing the delay because of the braking condition in
`set_mission_items` function
- This will not apply to Fixed wings
- The payload deploy getting triggered may be too early, as right now as
soon as the vehicle approaches the waypoint within the acceptance
threshold, the payload gets deployed
Add DO_GRIPPER support
Implement Gripper actual Hardware triggering support
- Currently not working, possibly in the mixer there's a bug
- Implemented the publishing of actuator_controls_1 uORB topic
- Implemented the test command for the payload_drop module, to test the
grpiper functionality
- Edited px4board file to include the payload_drop module
- Added Holybro X500 V2 airframe file, to enable testing on X500 V2
- Created new Quad X Payload Delivery mixer, which maps the actuator
controls 1 topic's data into the MAIN pin 5 output
Make Payload Drop Gripper Work
- Initialization of the Gripper position to CLOSED on Constructor of the
payload_drop module
- Setting the OPEN and CLOSED value to the appropriate actuator controls
input
Set vehicle_command_ack message's timestamp correctly
- By not setting the timestamp, the ack commands were not correctly
graphed in PlotJuggler!
Rename payload drop module to payload deliverer
- I think it's a more complex name (harder to type), but more generic
Add Gripper class (WIP)
Add Gripper class functionalities
- Add gripper uORB message
- Add gripper state machine
Use Gripper class as main interface in payload_deliverer
- Utilizes Gripper class functions for doing Gripper functionality
Remove mixer based package delivery trigger logic
- Remove custom mixer files that mapped actuator controls to outputs
statically
Additional improvements of the payload_deliverer
Fix payload_deliverer module not starting
- _task_id wasn't geting set appropriately in task_spawn function, which
led to runtime failure
Add Gripper Function to mixer_module
- Still not showing up as function mapping in QGC, needs fix
Add parameters to control gripper behavior
- Now user can enable / disable gripper
- Also select which type of gripper to use
Applying review from nuno
Remove timeout fetching from mission item and use gripper's timeout
- Previously, it was planned to use a custom DO_GRIPPER and DO_WINCH
MAVLink message definitions with information on timeout, but since now
we are using original message definition, only relevant timeout
information is defined in the payload_deliverer class
- This change brings in the timeout parameter to the Navigator, which
then sets the timeout in the mission_block class level, which then
processes the timeout logic
Make payload deployment work for Allmend test :P
Support gripper open/close test commands in payload_deliverer
Move enum definition for GRIPPER_ACTION to vehicle_command.msg
Remove double call for ` ${R}etc/init.d/rc.vehicle_setup`
- Was introduced during the rebase
- Was causing module already running & uORB topic can't be advertised
errors
Fix format via `make format` command
Modify S500 airframe file to use for control allocation usage
- Added Control allocation related parameters as default to not have it
reset every time the airframe is selected
Implement mission specific payload deploy timeout and more changes
Switch payload_deliverer to run on work queue
Remove unnecessary files
- Airframe changes from enabling control allocation are removed
Address review comments
- Remove debug messages
- Remove unnecessary or verbose comments & code
- Properly call parameter_update() function
Switch payload_deliverer to scheduled interval work item & refactor
- Switch to Schedeuled on Interval Work Item, as previous vehicle
command subscription callback based behavior led to vehicle comamnd ack
not being sent accordingly (since the Run() wouldn't be called unless
there's a new vehicle command), leading to ack command not being sent
out
- Also, old vehicle commands were getting fetched due to the
subscription callback as well, which was removed with this patch
- Fix the wrong population of floating point param2 field of vehicle
command by int8_t type gripper action by creating dedicated function
- Refactor and add comments to increase readability
Add gripper::grabbing() method and handle this in parameter update
- Previously, the intermediate state 'grabbing' was not considered, and
when the parameter update was called after the first initialization of
the gripper, the grab() function was being called again, which would
produce unnecessary duplicate vehicle command.
- Also replaced direct .grab() access to sending vehicle comamnd, which
unifies the gripper actuation mechanism through vehicle commands.
Navigator: Change SubscriptionData to Subscription to reduce memory usage
- Also removed unused vehicle command ack sub
PayloadDeliverer: Remove unnecessary changes & Bring back vehicle_command sub cb
When hitting zero thrust by stick there is 0 torque authority
without airmode. So 0% minimum manual thrust should never be the default
without airmode.
For SITL it's important that the GCS receives the first events messages
that reset the sequence number, in case the user does not press 'Disconnect'
when restarting SITL.
- new modules/simulation directory to collect all simulators and related modules
- new Tools/simulation directory to collect and organize scattered simulation submodules, scripts, etc
- simulation module renamed to simulator_mavlink
- sih renamed to simulator_sih (not a great name, but I wanted to be clear it was a simulator)
- ignition_simulator renamed to simulator_ignition_bridge
- large sitl_target.cmake split by simulation option and in some cases pushed to appropriate modules
- sitl targets broken down to what's actually available (eg jmavsim only has 1 model and 1 world)
- new Gazebo consistently referred to as Ignition for now (probably the least confusing thing until we fully drop Gazebo classic support someday)
Also remove the legacy "range aid" than can be achieved by setting the
height reference to range finder and the range finder control parameter
to "conditional".
Conditional range aiding cal also be set when the height reference isn't
the range finder. This prevents the ratchetting effect due to switching
between references.
- much simpler direct interface using Ignition Transport
- in tree models and worlds
- control allocation output configuration, no more magic actuator mapping to mavlink and back
- currently requires no custom Gazebo plugins (keeping things as lightweight and simple as possible)
Co-authored-by: Jaeyoung-Lim <jalim@ethz.ch>
This is the control surface type for airframes that have only a
single aileron servo or have the ailerons on a single output channel.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
For most VTOLs the param defaults for the agressiveness of the MC attitude controller
are too high, as VTOLs usually have high intertia and lot af drag due to wings and
can thus not rotate as fast as MCs.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
I think most vehicle can safely decend with at least 1.5m/s, and having this
value too low makes Descents/Landings/RTLs unnecessary long.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
The VTOL default was set to 1, while the param default is 1.5.
I don't see why it shuold be a different default for VTOLs and thus remove it.
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
- 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"
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.
- 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