Commit Graph

188 Commits

Author SHA1 Message Date
Beat Küng 1ad5a9de08 uorb: compress format definitions
Reduces flash usage by ~16KB.

- compress formats at build-time into a single string with all formats
- then at runtime iteratively decompress using
  https://github.com/atomicobject/heatshrink
2023-11-08 00:31:26 -05:00
Konrad e5e66370e7 FixedwingPositionControl: Add support for figure 8 loitering.
The command is sent by a dedicated mavlink command and forwarded to the fixed wing position controller.

The pattern is defined by the radius of the major axis, the radius of the minor axis and the orientation. The pattern is then defined by:
The upper part of the pattern consist of a clockwise circle with radius defined by the minor axis. The center of the circle is defined by the major axis minus the minor axis away from the pattern center.
The lower part of the pattern consist of a counter-clockwise circle with the same definitions as above.
In between, the circles are connected with straight lines in a cross configuration. The lines are always tangetial to the circles.
The orientation rotates the major axis around the NED down axis.

The loitering logic is defined inside its own class used by the fixed wing position control module. It defines which segment (one of the circles or lines) is active and uses the path controller (npfg or l1-control) to determine the desired roll angle.

A feedback mavlink message is send with the executed pattern parameters.
2023-10-31 15:57:59 -04:00
Peter van der Perk 019d232911 Add Zenoh pico support 2023-10-18 15:30:36 -04:00
Igor Mišić 208552fdab dataman: add DatamanClient with sync functions
Rework of dataman
2023-07-24 13:10:31 +02:00
Loic Fernau f8c9be087b
drivers: rework NXP UWB driver (#21124)
* UWB driver rework that uses 2 UWB MKBoards - 1 as Controller (Initiator), one as Controllee (Anchor)

Co-authored-by: NXPBrianna <108274268+NXPBrianna@users.noreply.github.com>
2023-07-12 11:44:23 -04:00
Niklas Hauser 8fe65c6722 Driver: Refactor MCP23009 GPIO expander into uORB driver 2023-06-19 07:58:21 +02:00
Silvan Fuhrer a1812dbde0 gimbal: move gimbal controls to new dedicated topic
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-16 11:55:45 +01:00
Silvan Fuhrer b16f16598b VTOL: remove virtual actuator_controls and instead use virtual torque/thrust topics
MC/FW rate controller and auto tuner: remove actuator_controls

AirshipAttControl: remove actuator_controls

MulticopterLandDetector: remove actuator_controls

mavlink streams vfr_hud and high_latency2: remove actuator_controls

RoverPositionController: remove actuator_controls

UUVAttitudeController: remove actuator_controls

battery: use length of thrust_setpoint for throttle compensation

VehicleMagnetometer: use length of thrust_setpoint for throttle compensation

Signed-off-by: Silvan Fuhrer
2023-03-16 11:55:45 +01:00
Silvan Fuhrer 1e56d9c219 Rework flaps/spoilers logic
- remove deprecated actuator_controls[INDEX_FLAPS/SPOILERS/AIRBRAKES]
- use new topic normalized_unsigned_setpoint.msg (with instances flaps_setpoint
and spoilers_setpoint) to pass into control allocation
- remove flaps/spoiler related fields from attitude_setpoint topic
- CA: add possibility to map flaps/spoilers to any control surface
- move flaps/spoiler pitch trimming to CA (previously called DTRIM_FLAPS/SPOILER)
- move manual flaps/spoiler handling from rate to attitude controller

FW Position controller: change how negative switch readings are intepreted
for flaps/spoilers (considered negative as 0).

VTOL: Rework spoiler publishing in hover

- pushlish spoiler_setpoint.msg in the VTOL module if in hover
- also set spoilers to land configuration if in Descend mode

Allocation: add slew rate limit of 0.5 to flaps/spoilers configuration change

Instead of doing the flaps/spoilers slew rate limiting in the FW Position Controller
(which then only is applied in Auto flight), do it consistently over all flight
modes, so also for manual modes.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 22:43:41 +01:00
Silvan Fuhrer 4b54ddfe61 Remove INDEX_COLLECTIVE_TILT from actuator_controls and instead use new topic tiltrotor_extra_controls
Tiltrotor_extra_controls also contains collective thrust beside collective tilt, as passing a 3D
thrust setpoint vector beside the tilt is not feasible.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 22:43:41 +01:00
Silvan Fuhrer dc4926dc4d remove WheelEncoders.msg
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 09:43:01 -05:00
Beat Küng 3f2336af32
navigator: add ModeCompleted signalling topic 2023-02-07 19:11:52 -05:00
Daniel Agar 54a32eb2f7
ekf2: EV overhaul yaw and position fusion (#20501)
- move EV yaw and EV position to new state machines
 - EV yaw and EV pos now configured via EKF2_EV_CTRL (migrated from EKF2_AID_MASK)
 - new EV position offset estimator to enable EV position while GPS position is active (no more EV pos delta fusion)
 - yaw_align now strictly means north (no more rotate external vision aid mask)
 - automatic switching between EV yaw, and yaw align north based on GPS quality
2022-12-20 10:23:56 -05:00
Zachary Lowell e4f641e9b5
Qurt qshell implementation (#20736) 2022-12-09 16:49:41 -05:00
Silvan Fuhrer 90e1f98c57 FW Launch Detection: refactor state machine and pubish launch_detection_status message
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-11-25 18:45:36 +01:00
Silvan Fuhrer a787a326e3 Fixed-wing: split out control of steering wheel into seperate message LandingGearWheel
Completely detach the steering wheel logic from the yaw controller (beside using the
same manual stick input in a manual flight mode).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-11-22 13:46:25 -05:00
Daniel Agar 9e7db0ed54
merge vehicle_angular_acceleration into vehicle_angular_velocity (#20531)
- vehicle_angular_velocity and vehicle_angular_acceleration are produced together from the same input data, consumed together, and share the the same metadata (timestamps)
 - individually these topics each have 16 bytes of metadata (2 timestamps) for 12 bytes of data (x,y,z float32)
2022-11-14 11:03:59 -05:00
Daniel Agar cea185268e
msg ROS2 compatibility, microdds_client improvements (timesync, reduced code size, added topics, etc), fastrtps purge
- 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)
2022-10-19 19:36:47 -04:00
Beat Küng d542ffc10c refactor vehicle_status_flags: rename to failsafe_flags 2022-10-13 16:05:25 -04:00
Beat Küng 455b885f86 commander: use new failsafe state machine and add user intention class 2022-10-11 22:31:20 -04:00
Daniel Agar bcdd2203d3 delete systemcmds/motor_test and msg/test_motor.msg 2022-09-09 09:14:09 -04:00
Junwoo Hwang 2542b1bb26 Implement Pacakge delivery via Gripper during mission
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
2022-09-07 08:11:52 +02:00
Beat Küng b7a6de05df arming checks: add health topic 2022-08-25 22:02:15 -04:00
bresch aba2eac0df ekf2: publish GNSS, rng and EV height biases 2022-08-24 09:16:11 -04:00
Daniel Agar 15223009d2 combine sensor_gps + vehicle_gps_position msgs (keeping separate topics) 2022-07-07 10:24:11 -04:00
Daniel Agar d5839e2dd5 optical flow sensor pipeline overhaul
- 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>
2022-06-20 20:56:56 -04:00
Alessandro Simovic de1fa11e96 New follow-me flight task
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 💄
2022-06-16 16:14:57 -04:00
Daniel Agar 1ae467e9cd ekf2: estimator aid source status (starting with fake position) 2022-05-23 16:21:49 -04:00
Igor Misic 08dcc72e1f commander/safety: replace safety.msg with Safety class (#19558) 2022-05-23 06:54:37 +02:00
Matthias Grob 8ca28f3796 Separate message for trajectory setpoint 2022-05-12 17:19:48 +02:00
Igor Misic 80aef942cd safety and safety button: refactoring #19413 2022-04-05 07:57:37 +02:00
Hovergames 457130fb69 Support for NXP UWB position sensor
uwb_sr150 driver for the sensor, and some
modifications in precision landing to allow
landing on a platform using the UWB system.
2022-04-04 17:26:52 +02:00
Daniel Agar 84e796c385 drives/gps: add new sensor_gnsss_relative msg
- for ublox this corresponds to NAV_RELPOSNED
2022-03-29 07:59:41 +02:00
Daniel Agar 0c31f63896 sensors: add baro calibration and cleanup
- 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
2022-03-26 16:08:41 -04:00
Daniel Mesham 06a9be74fa microdds: add xrce client 2022-03-22 09:01:05 +01:00
Daniel Agar 591b7b6934 ekf2: add new estimator_gps_status.msg
- includes the estimator status check fail bits broken out as descriptive booleans
 - absorbs ekf_gps_drift.msg
2022-02-21 08:58:59 -05:00
Roman Dvořák c8349811d1
Enable logging of mavlink tunnel messages
Co-authored-by: Vit Hanousek <vithanousek@seznam.cz>
2022-01-26 11:10:43 -05:00
Thomas Stastny 3b6c9448aa npfg: fix format CMakeLists 2022-01-14 22:05:53 +01:00
Thomas Stastny 082e320191 integrate optional NPFG library for wind-aware fixed-wing guidance 2022-01-14 22:05:53 +01:00
honglang b60e59d9be msg: new sensor_hygrometer msg 2021-12-27 12:13:09 -05:00
Beat Küng 4c80adfaf1 control_allocator: implement trim + slew rate limits configuration 2021-12-24 20:06:13 -05:00
Igor Mišić 72b1db4a63 pps_capture: implementation of pulse per second capture driver 2021-12-17 07:56:08 +01:00
Matthias Grob c522a8b15a Compute RTL time and react if lower than flight time
- Compute RTL time also during RTL
- Calculate correct altitude when finding destination
2021-11-24 14:10:24 +01:00
Beat Küng a0e43bca96 msg: remove unused vehicle_actuator_setpoint topic 2021-11-23 12:40:22 -05:00
Beat Küng 6fdcc43ea8 mixer_module: add testing for SYS_CTRL_ALLOC=1 with actuator_test cmd+uorb msg 2021-11-23 12:40:22 -05:00
bresch d47f9f155a MC mixer: replace multirotor_motor_limits by control_allocator_status
CA: fix saturation computation
Since the CA matrix is normalized, the same scale applied to be used when using the effectiveness matrix

MCRateControl: use control_allocator_status to get saturation info
2021-11-09 10:35:10 -05:00
Matthias Grob fabf865411 Use backwards compatible manual_control_setpoint instead of manual_control_input 2021-11-09 16:05:25 +01:00
Matthias Grob 956997eb1e Replace arm_request and mode_request with combined action_request
Which saves flash space, log size and is extensible to handle e.g.
the VTOL transition and future actions.
2021-11-09 16:05:25 +01:00
Matthias Grob 052e29267d Use mode_request for RC mode switching 2021-11-09 16:05:25 +01:00
Matthias Grob af607e3040 Use separate arm_request instead of vehicle_command for RC arming 2021-11-09 16:05:25 +01:00