- 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>
- 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>
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>
- 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>
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>
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>
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>
- 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
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.
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].
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>
- 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)
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.
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>
- 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)