Commit Graph

1540 Commits

Author SHA1 Message Date
Roman Bapst dd2322d622
Added PerformanceModel for fixed wing (#22091)
* created a Performance Model for fixed wing vehicle
- added compensation for maximum climbrate, minimum sinkrate, minimum airspeed and trim airspeed based on weight ratio and air density
- added atmosphere lib to standard atmosphere calculations


---------

Signed-off-by: RomanBapst <bapstroman@gmail.com>
Co-authored-by: Thomas Stastny <thomas.stastny@auterion.com>
2023-11-21 17:13:50 +01:00
Beat Küng 22acb08406 uorb: add message format compatibility check
This can be used by DDS/ROS 2 to check for matching message definitions.
2023-11-15 13:18:58 +01:00
Beat Küng bb900264e0 commander+mavlink: implement MAVLink standard modes 2023-11-15 13:18:58 +01:00
Beat Küng b46e1d744b commander: add config overrides 2023-11-15 13:18:58 +01:00
Beat Küng 889b6a1a78 commander: add VEHICLE_CMD_SET_NAV_STATE internal command 2023-11-15 13:18:58 +01:00
Beat Küng fbbccf6997 commander: implement external modes and mode executors 2023-11-15 13:18:58 +01:00
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
Silvan Fuhrer a47b684fd7 tecs_status.msg: directly add underspeed ratio to msg instead of boolean
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-11-07 12:18:06 -05:00
Silvan Fuhrer 8741a9784d TECS: remove TECS_MODE enum and instead add descriptive boolean flag to tecs_status
New flag: underspeed_mode_enabled.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-11-07 12:18:06 -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
Mathieu Bresciani 0d6c2c8ce9
EKF2: Error-State Kalman Filter (#22262)
* ekf derivation: change to error state formulation
* ekf2: update auto-generated code for error-state
* ekf2: adjust ekf2 code for error state formulation
* ekf2_tests: adjust unit tests for error-state EKF
* update change indicator for error-state EKF
* ekf2_derivation: allow disabling mag and wind states

---------

Co-authored-by: bresch <[brescianimathieu@gmail.com](mailto:brescianimathieu@gmail.com)>
2023-10-31 10:02:18 -04:00
Peter van der Perk 019d232911 Add Zenoh pico support 2023-10-18 15:30:36 -04:00
Daniel Agar 408c30de13
ekf2: delete redundant aid src status getters 2023-10-18 15:21:51 -04:00
Daniel Agar 5f87f3a046 ekf2: drag fusion add aid source status topic 2023-10-09 09:26:28 -04:00
Mathieu Bresciani d61743412c
ekf2: fix flow gyro bias corrections (#22145)
* ekf2-flow: fix flow gyro bias compensation
* ekf2-flow: apply flow gyro bias when used
* ekf2: log optical flow gyro bias
* ekf2: optical flow control always use provided flow gyro (with bias applied)
* ekf2-flow: log flow gyro and gyro reference
* ekf2-flow: support senrors with XY flow gyro

---------

Co-authored-by: Daniel Agar <daniel@agar.ca>
Co-authored-by: bresch <[brescianimathieu@gmail.com](mailto:brescianimathieu@gmail.com)>
2023-10-05 10:51:30 -04:00
Konrad 007ed11bbe Mission+RTL: Refactoring mission and RTL to keep them separate. RTL does all its mission related computation in its own class.
Dataman: Add write function to dataman cache.

RTL and mission have a new common base class mission_base. Both inherit from them and mission, RTL mission, and rtl reverse mission inherit from them and implement their desired functionalities. This simplifies the logic in mission as well as make the logic in rtl mission reverse and mission more readable.
Rtl mission reverse now functional again for VTOL flying back the mission and transitioning to MC at the home position.
Dataman cache has new write functionality to write to dataman while updating write item in its cache if necessary.
Dataman cache is now only updated when the respective module is active. Leads to a higher computation time once on activation, but decreases unnecessary cache updates when inactive.
2023-09-29 14:25:03 +02:00
Daniel Agar 14a967e2ca ekf2: remove aid src status fusion_enabled flag 2023-09-26 10:30:16 -04:00
Daniel Agar 10b54d08fc ekf2: add dedicated EKF2_CONFIG_TERRAIN in kconfig
- new estimator_aid_src_terrain_range_finder for HAGL RNG
2023-09-15 10:02:09 -04:00
Daniel Agar 7d497d4959 msg: set all ORB_QUEUE_LENGTH to actual rounded value 2023-09-08 15:28:16 -04:00
bresch 0aa4afdbce ekf2: add unaided_yaw for more resilient yaw control
This estimate doesn't converge to the true yaw but can be used as a
more consistent but drifting heading source.
It can be used by a setpoint generator to adjust its heading setpoint
while the true yaw estimate is converging in order to keep a constant
course over ground.
2023-08-30 09:56:19 +02:00
Beat Küng 03365658d5 VehicleControlMode: add flag_control_allocation_enabled
Allows (external) modes to directly publish actuator_{motors,servos}.
2023-08-21 20:53:51 -04:00
Mathieu Bresciani 74a54b3b12
EKF2: improve resilience against incorrect mag data
- when GNSS is used require low mag heading innovations during
  horizontal acceleration (yaw observable) to validate the mag
- only fuse mag heading just enough to constrain the yaw estimate
  variance to a sane value. Leave enough uncertainty to allow for a
  correction when the yaw is observable through GNSS fusion
2023-08-17 09:55:15 -04:00
Daniel Agar d75bb62a65
ekf2: separate mag and mag heading control logic (#21212)
- split mag_3d into new standalone mag fusion and mag fusion allowed to update all states (full mag_3d)
 - new dedicated control logic for mag/mag_3d fusion and standalone mag heading fusion
 - if WMM available use for mag_I and mag_B init
 - mag states reset if external yaw reset (yaw estimator, GPS yaw, etc)
 - mag reset if declination changed (eliminate _mag_yaw_reset_req)
 - mag fusion (but not mag_hdg or mag_3d) can be active during gps_yaw or ev_yaw (if yaw aligned north)

Co-authored-by: bresch <brescianimathieu@gmail.com>
2023-08-04 10:39:16 -04:00
Daniel Agar 88e7452492
commander: collapse ArmStateMachine and simplify
- simplify vehicle_status.arming_state down to just armed and disarmed
    - ARMING_STATE_INIT doesn't matter
    - ARMING_STATE_STANDBY is effectively pre_flight_checks_pass
    - ARMING_STATE_STANDBY_ERROR not needed
    - ARMING_STATE_SHUTDOWN effectively not used (all the poweroff/shutdown calls loop forever in place)
    - ARMING_STATE_IN_AIR_RESTORE doesn't exist anymore
 - collapse ArmStateMachine into commander
     - all requests already go through Commander::arm() and Commander::dismarm()
 - other minor changes
     - VEHICLE_CMD_DO_FLIGHTTERMINATION undocumented (unused?) test command (param1 > 1.5f) removed
     - switching to NAVIGATION_STATE_TERMINATION triggers parachute command centrally (only if armed)

---------

Co-authored-by: Matthias Grob <maetugr@gmail.com>
2023-07-28 17:12:01 -04:00
bresch 72be724b86 ekf2: log mag inclination and strength for tuning 2023-07-24 10:16:37 -04:00
Beat Küng 133aeb10a6 mision: only run mission feasibility checks when mission updated
Instead of also when geofence/safe points updated.
This prevents reporting multiple times.
2023-07-24 13:10:31 +02:00
Beat Küng 16a144c00f navigator: use mission topic to notify about geofence & safe point changes
This avoids the need to regularly access dataman for checking.
2023-07-24 13:10:31 +02:00
Igor Mišić c40a38bd88 dataman: remove locking mechanism 2023-07-24 13:10:31 +02:00
Igor Mišić 208552fdab dataman: add DatamanClient with sync functions
Rework of dataman
2023-07-24 13:10:31 +02:00
Matthias Grob 83b832fdce ManualControl: fix case where mode switches unintentionally in air
Case: A vehicle is already operating but has no stick input or another
source than RC. When RC stick input is switched to either because it gets
first time available or as a fallback to joystick then the mode was
immediately changed to the switch position. This can lead to loss of
control e.g. when the vehicle is flying far away and the
mode switch of the RC is in some fully manual piloted mode.

I added tests to cover the cases where RC mode initialization is expected
and also unexpceted because the vehicle is already armed.
2023-07-13 12:00:35 +02:00
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