Commit Graph

1510 Commits

Author SHA1 Message Date
Sergei Grichine f000238987 SensorGps.msg: switch to double precision for lat/lon/alt
To match https://github.com/PX4/PX4-GPSDrivers/pull/132 - adding high precision RTK lat/lon/alt components
2023-07-13 07:50:09 +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
alexklimaj acd19a0520 Ublox add UBX-RXM-RTCM for RTCM input status 2023-06-09 14:51:28 +12:00
mcsauder b8ad9bdbe5 Add magnetometer thermal compensation. 2023-06-07 12:07:29 -04:00
Christian Rauch e76c2b6a43
delete unused mavlink_px4.py & fix typos in VehicleCommand (#21332)
This file is not used anywhere neither in PX4-Autopilot, nor in the docs.

---------

Co-authored-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2023-04-20 07:50:58 +02:00
Silvan Fuhrer 460956fd33 TECS: revert altitude controller to old logic
- if the height rate input into TECS is finite, use that one to
update a velocity reference generator
- if the velocity reference generator reports position locked or
height rate input is not finite, then run altidue reference generator
- run altitude controller only if altitue is controlled

if height_rate_setpoint is set, only use that one to update altitdue trajectory

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-04-06 20:12:52 +02:00
Silvan Fuhrer dde656f4b1 TECS status: rename tecs_status.altitude_filtered to altitude_reference
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-04-06 20:12:52 +02:00
Silvan Fuhrer ac6c9c857a Gimbal: remove shutter and retraction handling
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-23 06:59:02 +01:00
Silvan Fuhrer 17cd65a239 Navigator: remove support for DO_SET_SERVO
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-16 11:55:45 +01: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 1218d9b2fc mavlink_mission: remove support for DO_SET_CAMERA_ZOOM
Camera controls should not happen through the flight controller, and
the control allocation has no means of controlling the camera zoom.

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
AlexKlimaj e375e02974 Add GPS spoofing state 2023-03-14 20:28:32 -04:00
Matthias Grob f498b90c41 mode_requirements: add manual control for manual modes 2023-03-08 09:32:56 +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 16594bffa9 Rework landing gear logic
- remove deprecated actuator_controls[INDEX_LANDING_GEAR]
- remove dead code in mc rate controller that used to prevent it from being retracted
on the ground (anyway had no effect as it only affected the actuator_control[LANDING_GEAR]
which wasn't sent to the control allocation)
- for VTOLs handle deployment/retraction of landing gear in AUTO  as a MC (retract if
more than 2m above ground, deploy if WP is a landing WP), plus additionally when transition
flight task is called (ALTITUDE mode and higher)
- for FW in AUTO: add logic in FW Position Controller, depending on waypoint type mainly
- manual landing gear settings always come through (a manual command overrides a previous
auto command, and vice-versa)

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
Eric Katzfey 5cade89499
Improve logging for Modal IO ESC (#21188)
- always publish esc_status
 - when enabled via MODAL_IO_VLOG param, enable actuator debug output

 - for modal_io commands, use ESC HW ID values instead of motor number for easier use
 - publish esc_status message for command line commands

 - Uncommented the code that fills in the cmdcount and power fields in the esc_status topic

---------

Co-authored-by: Travis Bottalico <travis@modalai.com>
2023-03-06 09:51:22 -05:00
Silvan Fuhrer dc4926dc4d remove WheelEncoders.msg
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-06 09:43:01 -05:00
Silvan Fuhrer 76116d79f9 TECS: remove umcommanded_descent flag
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-01 10:39:09 +01:00
Silvan Fuhrer 527225357b TECS: remove unused TECS_MODE_CLIMBOUT
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-03-01 10:39:09 +01:00
Silvan Fuhrer 526e066d9a Commander: rework GPS invalid warning to use estimator feedback instead of separate GPS quality thresholds
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-02-24 13:32:38 +01:00
Beat Küng 3f2336af32
navigator: add ModeCompleted signalling topic 2023-02-07 19:11:52 -05:00
Daniel Sahu fa6fda6cce
ekf2: new gravity observation (#21038)
Signed-off-by: Daniel M. Sahu <danielmohansahu@gmail.com>
2023-02-07 13:28:58 -05:00
Silvan Fuhrer 9b3a28dff5 Commander: add local_position_accuracy_low flag, incl. warning and RTL
Set this flag to true if local position is valid but accuracy low, such that
the operator can be warned before system switches to position-failure failsafe.
Additionally, switch to RTL if currently in Mission or Loiter to try to reach home
or fly out of GNSS-denied area.

Set low accuracy threshold to 50m by default for FW and VTOL.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-02-01 16:47:11 +01:00
Beat Küng b1709743f7 commander: add wind or flight time limit exceeded mode requirement
This prevents switching into any of these modes once the condition is set.
2023-02-01 08:48:09 +01:00
Hamish Willee f25abbc80a Fix magnetometer typo 2023-01-30 10:24:16 +01:00
Silvan Fuhrer d53d200aa5 Update msg/TecsStatus.msg
Co-authored-by: KonradRudin <98741601+KonradRudin@users.noreply.github.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 88ec117e59 TECS: rename tecs_status.altitude_filtered to altitude_sp_ref
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 06f4195663 PositionControllerStatus.msg: add comments
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer fc1c5da92c tecs_status.msg: add comments to states
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-26 17:04:43 +01:00
Silvan Fuhrer 148ffe4e25 add support for DO_CHANGE_ALTITUDE
Do the same as DO_REPOSITION wit only the altitude field populated
and MAV_DO_REPOSITION_FLAGS set, which means:
- switch to Loiter mode if not already in it
- set the current altitude to what is specified in the altitdue field,
keep current altitude setpoint otherwise
- keep current position setpoint
- fall back to current estimated position in case a position setpoint
is not finite

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-25 16:40:27 +01:00
bresch 6e30f8f5cb ekf2: use dedicated aid_src message for flow for terrain aiding 2023-01-21 15:31:19 -05:00
Daniel Agar 1aa8ec4537
drivers: initial VectorNav (VN-100, VN-200, VN-300) support 2023-01-20 19:09:30 -05:00
Jukka Laitinen 2985b5b9c2 msg/ActuatorTest.msg: Use default queue size the same as MAX_NUM_MOTORS
For the esc_calibration code, the actuator test is published for each motor
in a row. If the orb queue size is too small, messages are lost and not
received in mixer_module.

Set the default orb queue size of ActuatorTest high enough to keep the commands
for all motors in the queue.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2023-01-14 09:19:10 -05:00
Silvan Fuhrer 303b879748 VTOL/Commander: rename transition_failsafe to vtol_fixed_wing_system_failure
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-01-13 19:02:21 +03:00
Konrad f5524fa605 TECS: Combine both airspeed and airspeed derivative filters in TECS into one MIMO filter using a steady state Kalman filter. 2022-12-21 09:04:19 +01: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
Matthias Grob 331cb21dee manual_control_setpoint: change stick axes naming
In review it was requested to have a different name for
manual_control_setpoint.z because of the adjusted range.

I started to investigate what naming is most intuitive and found
that most people recognize the stick axes as roll, pitch, yaw, throttle.
It comes at no surprise because other autopilots
and APIs seem to share this convention.

While changing the code I realized that even within the code base
the axes are usually assigned to a variable with that name or
have comments next to the assignment clarifying the axes
using these names.
2022-11-28 19:25:55 +01:00
Matthias Grob 83246c84cf Switch manual_control_setpoint.z scaling from [0,1] to [-1,1]
To be consistent with all other axes of stick input and avoid future
rescaling confusion.

Note: for the MAVLink message 69 MANUAL_CONTROL it's using the full range
according to the message specs now [-1000,1000].
2022-11-28 19:25:55 +01: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
Silvan Fuhrer 6c611a7e8b VehicleAttitudeSetpoint: rename fw_control_yaw to fw_control_yaw_wheel to make usage clearer
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
Michael Schaeuble d7fde289de Use gimbal attitude for the camera feedback when available
The CameraFeedback module used only the vehicle attitude for the camera orientation so far. With this change, the gimbal_device_attitude_status is used to compute the global camera orientation when a gimbal is used.
2022-11-14 09:26:14 -05:00
Silvan Fuhrer 83e906e2e9 Control_allocator_status.msg: remove allocated_ fields
It's enough that the setpoints and the unallocated values are logged, from these
 the allocated values can be calculated if required.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-11-02 14:56:13 +01:00
Silvan Fuhrer bace45ba8d LandDetector: log rotational_movement
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-11-01 18:35:54 +01:00
JaeyoungLim a90857f651
FW separate reset integrals for messages (#20502)
This commit separates integral resets for attitude and rate control setpoints
2022-11-01 06:06:27 +01:00
Hamish Willee 96a305322a
params/uorb docs: rename mixer to control allocation (#20447) 2022-10-24 13:22:26 +02: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
Daniel Agar 535415a537 ekf2: add OF estimator aid src status 2022-10-18 14:19:16 -04:00
Silvan Fuhrer 5ea8c6e507 FlightTaskAuto: remove unused _getTargetVelocityXY()
Inclusive velocity_valid field in position_setpoint message that's then
no longer needed.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-17 16:12:15 -04:00
Silvan Fuhrer 42c613a0c7 position_setpoint.msg: remove unused alt_valid
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-17 16:12:15 -04:00
Silvan Fuhrer 42dd9b5063 position_setpoint.msg: remove unused velocity_frame field
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-17 16:12:15 -04:00
Beat Küng d542ffc10c refactor vehicle_status_flags: rename to failsafe_flags 2022-10-13 16:05:25 -04:00
Daniel Agar 2de990fd4b estimator_aid_source split GNSS pos (3d) -> pos (2d) + hgt
- per estimator air source status only keep a single set of flags and
timestamp that applies to the entire source
2022-10-13 11:28:50 -04:00
bresch 5f54f6fcda ekf2: migrate sideslip fusion to SymForce
- split fusion into update (compute innov and innov_var) and actual fusion to the state vector
- use estimator_aid_source_1d struct to group the data
2022-10-12 09:55:35 -04:00
Beat Küng 9b7a8d4568 vehicle_status_flags: add group 'Other' 2022-10-11 22:31:20 -04:00
Beat Küng 38d3739b6d refactor commander: rename rc_signal_lost -> manual_control_signal_lost, data_link_lost -> gcs_connection_lost 2022-10-11 22:31:20 -04:00
Beat Küng acaa50a448 geofence: add and report reason for violation 2022-10-11 22:31:20 -04:00
mcsauder ebc88afe46 Apply Google Style to Commander Private methods, rename geofence message geofence_violation to primary_geofence_breached. 2022-10-11 22:31:20 -04:00
Beat Küng e4bb219d10 vehicle_status_flags: cleanup message, move non-failsafe flags to vehicle_status 2022-10-11 22:31:20 -04:00
Beat Küng ae6377dfa0 mission_result: remove unused fields 2022-10-11 22:31:20 -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
Beat Küng a04230faa1 commander: add failsafe state machine with webassembly simulation
to run the simulation:
install sdk: https://emscripten.org/docs/getting_started/downloads.html
make run_failsafe_web_server
open http://0.0.0.0:8000/

Co-authored-by: Konrad <konrad@auterion.com>
2022-10-11 22:31:20 -04:00
Thomas Debrunner 0af87ec745 mavlink: initial OPEN_DRONE_ID_BASIC_ID/OPEN_DRONE_ID_LOCATION support 2022-10-04 14:40:59 -04:00
Silvan Fuhrer 34b6786f79 actuator_controls.msg: fix NUM_ACTUATOR_CONTROLS (9)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-09-29 14:25:16 -04:00
Roman Bapst 20457c5e2e
position_setpoint: replaced loiter_direction integer by boolean (#20317)
* position_setpoint: replaced loiter_direction integer by boolean (loiter_direction_counter_clockwise)

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-09-29 11:06:10 +02:00
chris1seto 77fdce9f3c
drivers/rc/crsf_rc: update standalone driver for CRSF and direct support for lq/rssi (#20084)
Co-authored-by: Chris Seto <chris1seto@gmail.com>
2022-09-23 19:19:25 -04:00
Daniel Agar 0a5c9d4951 position_setpoint delete unused landing_gear 2022-09-19 11:16:45 -04:00
Daniel Agar 11dd924bd4 position_setpoint delete unused SETPOINT_TYPE_FOLLOW_TARGET 2022-09-19 11:16:45 -04:00
Beniamino Pozzan 2e83c3a465 Fixed fastrtps version reading in microRTPS generation
Issue addressed: ROS2 is built from source and
no system-wide version of fastrtps is installed

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
2022-09-15 13:36:40 -04:00
bresch a54fa7b9b1 ekf2: add fake height fusion logic
When there is no vertical aiding, fake height is started to constrain
the vertical channel of the EKF
2022-09-10 12:29:29 -04:00
bresch aa716936bf ekf2: move synthetic_position flag to control_status.flags.fake_pos 2022-09-10 12:29:29 -04:00
Alvin Sun 238fdadfee Add attitude and bodyrate control to RTPS 2022-09-09 22:21:02 +02:00
Agata Barcis e268e69265 Fixed fastrtps version reading in microRTPS generation for ROS2 built from sources 2022-09-09 15:11:11 +01:00
Daniel Agar 15fece7e14 delete SYS_CTRL_ALLOC 2022-09-09 09:14:09 -04:00
Daniel Agar 13f9eabd70 delete unused actuator_controls_3 2022-09-09 09:14:09 -04:00
Daniel Agar 4ec9e2f216 uavcan: delete unused ESC idle and soft_stop 2022-09-09 09:14:09 -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 7e75b497ae
helicopter: add switch to engage main motor
For helicopters it's useful (e.g. during bringup) to be able to disable
the main rotor while the tail is still controlled to safely land.
2022-09-07 08:00:26 +02:00
Beat Küng f197c8884d commander: move esc checks to arming check 2022-09-01 17:07:23 -04:00
Beat Küng f17f38197d commander: move estimator checks to arming check 2022-09-01 17:07:23 -04:00
Beat Küng cfe3d793bf commander: move battery handling into arming checks 2022-09-01 17:07:23 -04:00
Beat Küng 13c93db11a commander: use circuit breaker params directly in arming checks 2022-08-25 22:02:15 -04:00
Beat Küng b2cb164c12 commander: replace health flags with health_report from arming checks 2022-08-25 22:02:15 -04:00
Beat Küng 6d1fb92eb7 commander: rework arming checks to use the events interface 2022-08-25 22:02:15 -04:00
Beat Küng 406b0bbc86 commander: handle VEHICLE_CMD_RUN_PREARM_CHECKS 2022-08-25 22:02:15 -04: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
Silvan Fuhrer a9b848cae3 FW attitue controller: fix publishing of rate controller status
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-19 09:40:48 +02:00
Silvan Fuhrer 5a2127d026 fixed-wing: update rate controller integrator handling
-always reset roll/pitch/yaw integrators at the same time
-reset them while waiting for launch or during FW Takeoff before Climbout
-reset wheel rate integrator only when disarmed

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-08-19 09:40:48 +02:00
Daniel Agar dfdfbbfa9c
msg/vehicle_odometry.msg: simplify covariance handling and update all usage (#19966)
- replace float32[21] URT covariances with smaller dedicated position/velocity/orientation variances (the crossterms are unused, awkward, and relatively costly)
 - these are easier to casually inspect and more representative of what's actually being used currently and reduces the size of vehicle_odometry_s quite a bit
 - ekf2: add new helper to get roll/pitch/yaw covariances
 - mavlink: receiver ODOMETRY handle more frame types for both pose (MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_ENU, MAV_FRAME_LOCAL_FRD, MAV_FRAME_LOCAL_FLU) and velocity (MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_ENU, MAV_FRAME_LOCAL_FRD, MAV_FRAME_LOCAL_FLU, MAV_FRAME_BODY_FRD)
 - mavlink: delete unused ATT_POS_MOCAP stream (this is just a passthrough)

Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2022-08-04 12:55:21 -04:00
RomanBapst a425bc4c92 vehicle_local_position: fixed comment
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-08-02 15:29:25 +02:00
Hamish Willee 30e2490d5b
Docs are now in user guide and main (#19977)
* Fix links to docs in source to point to docs on main not master

* More docs and scripts that need to point to main
2022-08-01 11:39:39 +10:00
Daniel Agar 41d9c3dd2a ekf2: add AUX velocity aid src status
- also includes velocity and position helpers for using estimator aid
   source status messages that will later be used for GPS, EV, etc
2022-07-29 12:02:31 -04:00
Daniel Agar a397c09e59 ekf2: use estimator_aid_src for all yaw sources (mag, gnss, ev) 2022-07-29 11:20:48 -04:00