Compare commits

...

23 Commits

Author SHA1 Message Date
chfriedrich98 79043dd5c7 boat: add module for rudder-steered boats 2025-09-05 13:48:57 +02:00
chfriedrich98 9c38602c12 sv: rename rover parameters to surface vehicle 2025-09-05 13:48:17 +02:00
chfriedrich98 fb05dedb7b sv: extend rover control lib to surface vehicles 2025-09-05 13:28:30 +02:00
chfriedrich98 ae65b33ba0 rover: apply sp renaming to rover modules 2025-09-05 08:41:59 +02:00
chfriedrich98 7670989769 sv: rename rover sp to surface vehicle 2025-09-05 08:27:58 +02:00
alexklimaj 89c6d24946 Update GPS submodule 2025-09-04 17:02:31 -06:00
Alex Klimaj af6bf931c1 uavcan bootloader watchdog_pet during long flashes (#25523) 2025-09-04 12:20:03 -08:00
fbaklanov fc8e2021e7 A driver for EULER-NAV Baro-Inertial AHRS (#24534)
* Create a dummy BAHRS driver

* Resolve compilation

* Switch back to cpp, fix compilation

* Create module.yaml

* Implement required module APIs and open serial port

* Revise info and error messages

* Poll serial port

* Push received bytes into the ring buffer

* Process data buffer (1)

* Process data buffer (2)

* Process data buffer (3)

* Process data buffer (4)

* Process data buffer (5)

* Process data buffer (6)

* Implement and use initialize() and deinitialize() methods

* Implement print_usage() and print_status()

* Collect all config constants in a class

* Put info about next found message into a class

* Print CRC failure count

* Remove unneeded print

* Add comments

* Disable EKF2, advertise vehicle attitude

* Decode and publish BAHRS signals (1)

* Run the driver as an additional source of sensor signals

* Add tiny noise to baro-inertial pressure signal

* Fix the sensor ID

* Add copyrights

* Fix formatting

* Remove redundant newline character

* Fix long parameter name

* Fix findings (1)

* Fix finding (2)

* Fix formatting

* Fix the timeout value

* Remove aliases

* Fix copyright

* Fix indent

* Comply with naming convention

* Rework comparison to false

* Reduce nesting (1)

* Reduce nesting (2)

* Reduce nesting (3)

* Fix BAHRS sensor ID
2025-09-04 09:31:36 -08:00
Silvan Fuhrer e6f60ef403 Sensors: remove some distance sensors from COMMON_DISTANCE_SENSOR again (#25522)
* distance sensors common: remove DISTANCE_SENSOR_TERARANGER

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

* distance sensors common: remove DISTANCE_SENSOR_CM8JL65

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

---------

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2025-09-04 09:28:37 -08:00
Pedro Roque 944b3e763a doc: Change email for Pedro Roque (#25514) 2025-09-02 16:07:55 -08:00
Pedro Roque 271cb49597 feat: airframe documentation for spacecraft (#25294) 2025-09-02 16:27:26 -07:00
Alexander Lerach 9015001b42 uavcan: fix driver init after stop/start (#25511) 2025-09-02 10:02:15 -08:00
Silvan ce207837cf rc.sensors: add iis2mdc mag to list of probed for sensors
Signed-off-by: Silvan <silvan@auterion.com>
2025-09-02 10:16:32 -06:00
Niklas Hauser 3a734bc846 [board] Add PCA9685 driver to FMUv6s board 2025-08-29 14:05:40 +02:00
Niklas Hauser 9062d0cc7d [driver] Add a parameter to enable the PCA9685 driver 2025-08-29 14:05:40 +02:00
Niklas Hauser b2b80e8075 [board] Reformat FMUv6s init script to start internal sensor first 2025-08-29 14:05:40 +02:00
Balduin 2eac6cca38 dds_topics: accept landing_gear command from external modes (#25496) 2025-08-28 08:30:27 -08:00
Claudio Chies fe1abb5b92 the PR has long been merged (#25495) 2025-08-28 08:28:44 -08:00
Marco Hauswirth 073013cf85 reset terrain w flow based on current horizontal velocity 2025-08-28 13:58:29 +02:00
Silvan Fuhrer 547582b16b DSHOT: fix unit for DSHOT_MIN parameter (#25493)
Signed-off-by: Silvan <silvan@auterion.com>
2025-08-27 09:21:16 -08:00
Alexander Lerach 8f2c36689d logging: allow logging backend config
* logging: allow logging backend config

* correct board comments

* documentation: updated logging section
2025-08-27 15:44:36 +02:00
Jacob Dahl 30fcb4fcb1 uavcan: esc: init msg to avoid publishing random values (#25485) 2025-08-27 17:09:36 +12:00
Davide Iafrate ec436d3be3 Enable selectively disabling sensors in the Gazebo bridge. (#25484)
* Initial plan

* Add configurable sensor subscription parameters

Co-authored-by: Tuxliri <3532595+Tuxliri@users.noreply.github.com>

---------

Co-authored-by: copilot-swe-agent[bot] <198982749+Copilot@users.noreply.github.com>
Co-authored-by: Tuxliri <3532595+Tuxliri@users.noreply.github.com>
2025-08-26 10:00:47 -08:00
141 changed files with 5980 additions and 1300 deletions
+1 -1
View File
@@ -19,7 +19,7 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma
| Matthias Grob | Multirotor | [@MaEtUgR](https://github.com/MaEtUgR) | maetugr |
| Silvan Fuhrer | Fixed-Wing / VTOL | [@sfuhrer](https://github.com/sfuhrer) | sfuhrer |
| Christian Friedrich | Rover | [@chfriedrich98](https://github.com/chfriedrich98) | christian982564 |
| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | <padr@kth.se>
| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | <roque@caltech.edu>
| Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | <dahl.jakejacob@gmail.com>
@@ -1,10 +1,21 @@
#!/bin/sh
#
# @name 3DoF Spacecraft Model
# @name KTH-ATMOS
#
# @type 2D Freeflyer with 8 thrusters - Planar motion
# @type Free-Flyer
# @class Spacecraft
#
# @maintainer Pedro Roque <padr@kth.se>
# @output Motor1 back left thruster, +x thrust
# @output Motor2 front left thruster, -x thrust
# @output Motor3 back right thruster, +x thrust
# @output Motor4 front right thruster, -x thrust
# @output Motor5 front left thruster, +y thrust
# @output Motor6 front right thruster, -y thrust
# @output Motor7 back left thruster, +y thrust
# @output Motor8 back right thruster, -y thrust
#
# @maintainer discower-io
# @url https://atmos.discower.io
#
. ${R}etc/init.d/rc.sc_defaults
+14 -7
View File
@@ -54,6 +54,13 @@ if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL)
)
endif()
if(CONFIG_MODULES_BOAT_RUDDER)
px4_add_romfs_files(
rc.boat_rudder_apps
rc.boat_rudder_defaults
)
endif()
if(CONFIG_MODULES_FW_RATE_CONTROL)
px4_add_romfs_files(
rc.fw_apps
@@ -83,13 +90,6 @@ if(CONFIG_MODULES_ROVER_ACKERMANN)
)
endif()
if(CONFIG_MODULES_SPACECRAFT)
px4_add_romfs_files(
rc.sc_apps
rc.sc_defaults
)
endif()
if(CONFIG_MODULES_ROVER_MECANUM)
px4_add_romfs_files(
rc.rover_mecanum_apps
@@ -97,6 +97,13 @@ if(CONFIG_MODULES_ROVER_MECANUM)
)
endif()
if(CONFIG_MODULES_SPACECRAFT)
px4_add_romfs_files(
rc.sc_apps
rc.sc_defaults
)
endif()
if(CONFIG_MODULES_UUV_ATT_CONTROL)
px4_add_romfs_files(
rc.uuv_apps
@@ -5,7 +5,17 @@
# @type Free-Flyer
# @class Spacecraft
#
# @output Motor1 back left thruster, +x thrust
# @output Motor2 front left thruster, -x thrust
# @output Motor3 back right thruster, +x thrust
# @output Motor4 front right thruster, -x thrust
# @output Motor5 front left thruster, +y thrust
# @output Motor6 front right thruster, -y thrust
# @output Motor7 back left thruster, +y thrust
# @output Motor8 back right thruster, -y thrust
#
# @maintainer DISCOWER
# @url https://atmos.discower.io
#
. ${R}etc/init.d/rc.sc_defaults
@@ -0,0 +1,8 @@
#!/bin/sh
# Standard apps for a boat rudder.
# Start boat rudder module.
boat_rudder start
# Start Land Detector.
land_detector start rover
@@ -0,0 +1,11 @@
#!/bin/sh
# Rudder-steered boats parameters.
set VEHICLE_TYPE boat
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER
param set-default CA_AIRFRAME 5 # Rover (Ackermann)
param set-default CA_R_REV 1 # Motor is assumed to be reversible
param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying
param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius
param set-default EKF2_GBIAS_INIT 0.01
param set-default EKF2_ANGERR_INIT 0.01
+24 -1
View File
@@ -8,6 +8,9 @@
# End Setup for board specific configurations. #
###############################################################################
#
# Set SD logging mode
#
if param compare SDLOG_MODE 1
then
set LOGGER_ARGS "${LOGGER_ARGS} -e"
@@ -28,8 +31,28 @@ then
set LOGGER_ARGS "${LOGGER_ARGS} -a"
fi
#
# Set logging backend
#
if param compare SDLOG_BACKEND 1
then
set LOGGER_ARGS "${LOGGER_ARGS} -m file"
fi
if ! param compare SDLOG_MODE -1
if param compare SDLOG_BACKEND 2
then
set LOGGER_ARGS "${LOGGER_ARGS} -m mavlink"
fi
if param compare SDLOG_BACKEND 3
then
set LOGGER_ARGS "${LOGGER_ARGS} -m all"
fi
#
# Start logger if any logging backend is enabled
#
if ! param compare SDLOG_BACKEND 0
then
logger start -b ${LOGGER_BUF} -t ${LOGGER_ARGS}
fi
+1
View File
@@ -237,6 +237,7 @@ then
qmc5883p -X -q start
rm3100 -X -q start
bmm350 -X -q start
iis2mdc -X -q start
# start last (wait for possible icm20948 passthrough mode)
ak09916 -X -q start
+2 -1
View File
@@ -14,7 +14,6 @@ class AirframeGroup(object):
self.af_class = af_class
self.airframes = []
def AddAirframe(self, airframe):
"""
Add airframe to the airframe group
@@ -107,6 +106,8 @@ class AirframeGroup(object):
return "Balloon"
elif (self.type == "Vectored 6 DOF UUV"):
return "Vectored6DofUUV"
elif self.type == "Free-Flyer":
return "FreeFlyer"
return "AirframeUnknown"
def GetAirframes(self):
+1
View File
@@ -21,6 +21,7 @@ CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DATAMAN_PERSISTENT_STORAGE=n
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
@@ -14,7 +14,7 @@ param set-default SYS_DM_BACKEND 1
# Set TELEM1 as default mavlink connection
param set-default MAV_0_CONFIG 0
# Disable logger writing to FRAM, only stream over MAVLINK
set LOGGER_ARGS "-m mavlink"
param set-default SDLOG_BACKEND 2
# 200kOhm/10kOhm voltage divider on V_BAT
param set-default BAT1_V_DIV 21
+17 -11
View File
@@ -12,17 +12,20 @@ board_adc start
bmi088 -A -R 0 -s start
bmi088 -G -R 0 -s start
# MAG on I2C4, ROTATION_ROLL_180=8
if ver hwtypecmp V6S013 V6S015
then
# Revision(s) with BMM150
# MAG on I2C4, ROTATION_ROLL_180=8
bmm150 -I -R 8 start
else
# Revision(s) with BMM350
# MAG on I2C4, ROTATION_ROLL_180=8
bmm350 -I -R 8 start
fi
# BARO on I2C4
bmp388 -I -b 4 -a 0x77 start
# External sensors on I2C1
if param compare SENS_EN_INA226 1
then
# Start Digital power monitors
@@ -59,14 +62,17 @@ fi
if param compare BAT1_V_CHANNEL -2
then
if [ "$INA_CONFIGURED" != "yes" ]
then
param set BAT1_V_CHANNEL -1
fi
if [ "$INA_CONFIGURED" != "yes" ]
then
param set BAT1_V_CHANNEL -1
fi
fi
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
# External compass IST8310 on I2C1
ist8310 -X -b 1 -R 10 start
# BARO on I2C4
bmp388 -I -b 4 -a 0x77 start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start -b 1
fi
@@ -38,5 +38,5 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Don't try to log onto SD card
param set-default SDLOG_MODE -1
# Disable logging
param set-default SDLOG_BACKEND 0
@@ -38,5 +38,5 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Don't try to log onto SD card
param set-default SDLOG_MODE -1
# Disable logging
param set-default SDLOG_BACKEND 0
+197
View File
@@ -0,0 +1,197 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 19.2.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
version="1.1"
id="draw"
x="0px"
y="0px"
viewBox="0 0 291.424 291.77"
enable-background="new 0 0 291.424 291.77"
xml:space="preserve"
sodipodi:docname="FreeFlyer.svg"
inkscape:version="1.2.2 (b0a8486541, 2022-12-01)"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns="http://www.w3.org/2000/svg"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:dc="http://purl.org/dc/elements/1.1/"><metadata
id="metadata13908"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title>QuadRotorX</dc:title></cc:Work></rdf:RDF></metadata><defs
id="defs13906"><rect
x="64.295094"
y="257.16159"
width="20.004284"
height="19.434001"
id="rect1674" /><rect
x="57.181928"
y="12.768183"
width="21.455602"
height="14.069247"
id="rect1668" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-3" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-6" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-8" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0-3" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0-5" /></defs><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1920"
inkscape:window-height="1131"
id="namedview13904"
showgrid="true"
showguides="false"
inkscape:zoom="2"
inkscape:cx="37"
inkscape:cy="143.75"
inkscape:window-x="0"
inkscape:window-y="0"
inkscape:window-maximized="1"
inkscape:current-layer="draw"
inkscape:showpageshadow="2"
inkscape:pagecheckerboard="0"
inkscape:deskcolor="#d1d1d1"><inkscape:grid
type="xygrid"
id="grid14610" /></sodipodi:namedview><title
id="title13869">QuadRotorX</title>
<rect
style="fill:#4ec3e8;fill-opacity:0.8;stroke-width:0.703099"
id="rect866"
width="182.87863"
height="182.87863"
x="54.336742"
y="54.008221" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 41.75804,283.31181 64.75142,-0.1091 -34.35904,-46.53234"
id="path978" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 8.0625538,189.05596 0.1091,64.75142 46.5323452,-34.35904"
id="path978-3" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 7.6111718,42.233006 0.1091,64.751414 46.5323442,-34.359034"
id="path978-3-5" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="M 283.3143,102.92315 283.2052,38.171731 236.67284,72.530766"
id="path978-3-0" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 283.76568,249.7461 -0.1091,-64.75142 -46.53235,34.35904"
id="path978-3-5-9" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 186.0159,282.76127 64.75142,-0.1091 -34.35904,-46.53235"
id="path978-5" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 249.48837,7.3723165 -64.75142,0.1091 34.35904,46.5323455"
id="path978-6" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="M 105.23051,7.9228645 40.479095,8.0319644 74.838131,54.56431"
id="path978-5-2" /><path
fill="#ffffff"
stroke="#000000"
stroke-miterlimit="10"
d="m 177.46535,152.08429 -25.44869,25.44869 c -2.72029,2.72029 -7.13013,2.72029 -9.84972,0 l -25.44868,-25.44869 c -2.7203,-2.72029 -2.7203,-7.13013 0,-9.84972 l 25.44868,-25.44868 c 2.72029,-2.72029 7.13013,-2.72029 9.84972,0 l 25.44869,25.44868 c 2.72029,2.72029 2.72029,7.13013 0,9.84972 z"
id="path13875-2"
style="stroke-width:0.703099" /><polygon
fill="#ff442b"
stroke="#000000"
stroke-miterlimit="10"
points="145.645,117.211 163.823,168.211 127.468,168.211 "
id="polygon13877-7"
transform="matrix(0.70309945,0,0,0.70309945,44.68853,44.358917)" /><text
xml:space="preserve"
id="text1666"
style="fill:#ffffff;fill-opacity:0.80000001;white-space:pre;shape-inside:url(#rect1668)" /><text
xml:space="preserve"
id="text1672"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674);fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-56.149908,-232.98716)"><tspan
x="64.294922"
y="271.72011"
id="tspan2022">1</tspan></text><text
xml:space="preserve"
id="text1672-6"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-3);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-54.90599,-471.96664)"><tspan
x="64.294922"
y="271.72011"
id="tspan2024">2</tspan></text><text
xml:space="preserve"
id="text1672-1"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-6);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,88.181331,-233.48182)"><tspan
x="64.294922"
y="271.72011"
id="tspan2026">3</tspan></text><text
xml:space="preserve"
id="text1672-7"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-8);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,89.923516,-472.9994)"><tspan
x="64.294922"
y="271.72011"
id="tspan2028">4</tspan></text><text
xml:space="preserve"
id="text1672-2"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-107.88311,-425.85878)"><tspan
x="64.294922"
y="271.72011"
id="tspan2030">5</tspan></text><text
xml:space="preserve"
id="text1672-2-2"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,140.31603,-426.60417)"><tspan
x="64.294922"
y="271.72011"
id="tspan2032">6</tspan></text><text
xml:space="preserve"
id="text1672-2-2-7"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0-3);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-106.57328,-277.85487)"><tspan
x="64.294922"
y="271.72011"
id="tspan2034">7</tspan></text><text
xml:space="preserve"
id="text1672-2-2-9"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0-5);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,140.59859,-279.63807)"><tspan
x="64.294922"
y="271.72011"
id="tspan2036">8</tspan></text></svg>

After

Width:  |  Height:  |  Size: 7.4 KiB

+3 -2
View File
@@ -35,14 +35,15 @@ The parameters you are most likely to change are listed below.
| Parameter | Description |
| ------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `-1`: Logging disabled.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.<br />- bit `0`: SD card logging.</br >- bit `1`: Mavlink logging.
| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). |
| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".<br>This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. |
Useful settings for specific cases:
- Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE).
- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE)
- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND)
### Logger module
-6
View File
@@ -3,12 +3,6 @@
[Rotoye Batmon](https://rotoye.com/batmon/) is a kit for adding smart battery functionality to off-the-shelf Lithium-Ion and LiPo batteries.
It can be purchased as a standalone unit or as part of a factory-assembled smart-battery.
::: info
At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware).
Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723).
:::
![Rotoye Batmon Board](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg)
![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg)
+9 -9
View File
@@ -176,15 +176,6 @@ set(msg_files
RateCtrlStatus.msg
RcChannels.msg
RcParameterMap.msg
RoverAttitudeSetpoint.msg
RoverAttitudeStatus.msg
RoverPositionSetpoint.msg
RoverRateSetpoint.msg
RoverRateStatus.msg
RoverSpeedSetpoint.msg
RoverSpeedStatus.msg
RoverSteeringSetpoint.msg
RoverThrottleSetpoint.msg
Rpm.msg
RtlStatus.msg
RtlTimeEstimate.msg
@@ -208,6 +199,15 @@ set(msg_files
SensorsStatusImu.msg
SensorUwb.msg
SensorAirflow.msg
SurfaceVehicleAttitudeSetpoint.msg
SurfaceVehicleAttitudeStatus.msg
SurfaceVehiclePositionSetpoint.msg
SurfaceVehicleRateSetpoint.msg
SurfaceVehicleRateStatus.msg
SurfaceVehicleSpeedSetpoint.msg
SurfaceVehicleSpeedStatus.msg
SurfaceVehicleSteeringSetpoint.msg
SurfaceVehicleThrottleSetpoint.msg
SystemPower.msg
TakeoffStatus.msg
TaskStackInfo.msg
@@ -1,4 +1,4 @@
# Rover Attitude Setpoint
# Surface Vehicle Attitude Setpoint
uint64 timestamp # [us] Time since system start
float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint
@@ -1,5 +1,5 @@
# Rover Attitude Status
# Surface Vehicle Attitude Status
uint64 timestamp # [us] Time since system start
float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw
float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED] Measured yaw
float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates)
@@ -1,8 +1,8 @@
# Rover Position Setpoint
# Surface Vehicle Position Setpoint
uint64 timestamp # [us] Time since system start
float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position
float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track
float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed
float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with
float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel
float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the vehicle should arrive at the target with
float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Omnidirectional only: Specify vehicle yaw during travel
@@ -1,4 +1,4 @@
# Rover Rate setpoint
# Surface Vehicle Rate setpoint
uint64 timestamp # [us] Time since system start
float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint
@@ -1,4 +1,4 @@
# Rover Rate Status
# Surface Vehicle Rate Status
uint64 timestamp # [us] Time since system start
float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate
@@ -1,5 +1,5 @@
# Rover Speed Setpoint
# Surface Vehicle Speed Setpoint
uint64 timestamp # [us] Time since system start
float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction
float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction
float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not omnidirectional] Omnidirectional only: Speed setpoint in body y direction
@@ -1,9 +1,9 @@
# Rover Velocity Status
# Surface Vehicle Velocity Status
uint64 timestamp # [us] Time since system start
float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction
float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates)
float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction
float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction
float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates)
float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction
float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not omnidirectional] Omnidirectional only: Measured speed in body y direction
float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not omnidirectional] Omnidirectional only: Speed setpoint in body y direction that is being tracked (Applied slew rates)
float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not omnidirectional] Omnidirectional only: Integral of the PID for the closed loop controller of the speed in body y direction
@@ -1,4 +1,4 @@
# Rover Steering setpoint
# Surface Vehicle Steering setpoint
uint64 timestamp # [us] Time since system start
float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels
float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Omnidirectional: Normalized speed difference between the left and right wheels
@@ -1,5 +1,5 @@
# Rover Throttle setpoint
# Surface Vehicle Throttle setpoint
uint64 timestamp # [us] Time since system start
float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis
float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis
float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not omnidirectional] Omnidirectional only: Throttle setpoint along body Y axis
@@ -847,6 +847,8 @@ static flash_error_t file_read_and_program(const uavcan_Path_t *fw_path, uint8_t
request.offset += length;
bootloader.percentage_done = (request.offset / a_percent);
watchdog_pet();
} while (request.offset < fw_image_size &&
length == sizeof(response.data) &&
flash_status == FLASH_OK);
-2
View File
@@ -2,11 +2,9 @@ menu "Distance sensors"
menuconfig COMMON_DISTANCE_SENSOR
bool "Common distance sensor's"
default n
select DRIVERS_DISTANCE_SENSOR_CM8JL65
select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C
select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL
select DRIVERS_DISTANCE_SENSOR_LL40LS
select DRIVERS_DISTANCE_SENSOR_TERARANGER
select DRIVERS_DISTANCE_SENSOR_TF02PRO
select DRIVERS_DISTANCE_SENSOR_TFMINI
select DRIVERS_DISTANCE_SENSOR_ULANDING_RADAR
+1
View File
@@ -254,6 +254,7 @@
#define DRV_INS_DEVTYPE_ILABS 0xE9
#define DRV_INS_DEVTYPE_MICROSTRAIN 0xEA
#define DRV_INS_DEVTYPE_BAHRS 0xEB
#define DRV_DEVTYPE_UNUSED 0xff
+1 -1
View File
@@ -16,7 +16,7 @@ parameters:
sure to set this high enough so that the motors are always spinning while
armed.
type: float
unit: '%'
unit: norm
min: 0
max: 1
decimal: 2
+1
View File
@@ -5,6 +5,7 @@ menu "Inertial Navigation Systems (INS)"
select DRIVERS_INS_VECTORNAV
select DRIVERS_INS_ILABS
select DRIVERS_INS_MICROSTRAIN
select DRIVERS_INS_EULERNAV_BAHRS
---help---
Enable default set of INS sensors
rsource "*/Kconfig"
@@ -0,0 +1,44 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__ins__eulerav_bahrs
MAIN eulernav_bahrs
INCLUDES
bahrs
SRCS
eulernav_bahrs_main.cpp
eulernav_driver.cpp
eulernav_driver.h
DEPENDS
ringbuffer
)
+5
View File
@@ -0,0 +1,5 @@
menuconfig DRIVERS_INS_EULERNAV_BAHRS
bool "eulernav_bahrs"
default n
---help---
Enable support for EULER-NAV Baro-Inertial AHRS
@@ -0,0 +1,371 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* The header is a modified version of a header from this repo:
* https://github.com/euler-nav/bahrs-oss
*
* Copyright 2023 AMS Advanced Air Mobility Sensors UG
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED.IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#pragma once
#include <stdint.h>
#define PROTOCOL_WORD_LEN (4)
#define PADDING_SIZE(SPayloadType) (PROTOCOL_WORD_LEN - ((sizeof(SMessageHeader) + sizeof(SPayloadType)) % PROTOCOL_WORD_LEN))
#define BIT_VALID_HEIGHT (0x01)
#define BIT_VALID_VELOCITY_DOWN (0x02)
#define BIT_VALID_ROLL (0x04)
#define BIT_VALID_PITCH (0x08)
#define BIT_VALID_MAGNETIC_HEADING (0x10)
#define BIT_VALID_SPECIFIC_FORCE_X (0x01)
#define BIT_VALID_SPECIFIC_FORCE_Y (0x02)
#define BIT_VALID_SPECIFIC_FORCE_Z (0x04)
#define BIT_VALID_ANGULAR_RATE_X (0x08)
#define BIT_VALID_ANGULAR_RATE_Y (0x10)
#define BIT_VALID_ANGULAR_RATE_Z (0x20)
/**
* @brief The class that describes and implements the BAHRS serial protocol.
*/
class CSerialProtocol
{
public:
static constexpr uint8_t uMarker1_ { 0x4E }; ///< Sync byte 1, symbol 'N'
static constexpr uint8_t uMarker2_ { 0x45 }; ///< Sync char 2, symbol 'E'
static constexpr uint16_t uVersion_ { 2U }; ///< Protocol version
static constexpr float skfSpecificForceScale_ { 1.495384e-3F }; ///< Integer to float, +-5g range
static constexpr float skfAngularRateScale_ { 1.597921e-4F }; ///< Integer to float, +-300 deg/s range
static constexpr float skfHeightScale_ { 0.16784924F }; ///< Integer to float, -1000 to 10000 m range
static constexpr float skfHeighOffset_ { 1000.0F }; ///< An offset to convert unsigned integer to float
static constexpr float skfVelocityDownScale_ { 9.155413e-3F }; ///< Integer to float, -300 to 300 m/s range
static constexpr float skfAngleScale_ { 9.587526e-5F }; ///< Integer to float, -pi to pi or 0 to 2 pi range
// Signal ranges
static constexpr float skfMaxHeight_ { 10000.0F };
static constexpr float skfMinHeight_ { -1000.0F };
static constexpr float skfMaxVelocityDown_ { 300.0F };
static constexpr float skfMinVelocityDown_ { -300.0F };
enum class EMessageIds : uint8_t {
eInvalid = 0x00, ///< Invalid
eInertialData = 0x01, ///< Inertial data message
eNavigationData = 0x02, ///< Navigation data message
eAccuracy = 0x03, ///< Attitude accuracy information
eTimeOfNavigationData = 0x04, ///< "Time of navigation data" message
eTimeOfInertialData = 0x05, ///< "Time of inertial data" message
eTimeOfSyncPulse = 0x06, ///< "Time of the latest sync pulse" message
eSoftwareVersion = 0x0F, ///< "Software version" message
eDebugEventWriteToPort = 0xC0, ///< Debug information: SWC port data
eDebugEventRunnableCall = 0xC1, ///< Debug information: SWC API call
eTypeOpenDiagnostic = 0xF0, ///< Request to enter diagnostics mode
eTypeCloseDiagnostic = 0xF1, ///< Request to exit diagnostics mode
eTypeReadNVMPage = 0xF2, ///< Request to read NVM page
eTypeNVMPageData = 0xF3, ///< A message with NVM page data
eTypeAccept = 0xFF ///< Acknowledgment of diagnostics message reception
};
typedef uint32_t CrcType_t;
#pragma pack(push, 1)
/**
* @brief Message header struct.
*/
struct SMessageHeader {
uint8_t uMarker1_ { 0x4E };
uint8_t uMarker2_ { 0x45 };
uint16_t uVersion_ { CSerialProtocol::uVersion_ };
uint8_t uMsgType_ { 0U };
};
/**
* @brief Inertial data message payload.
*/
struct SInertialData {
uint8_t uSequenceCounter_ { 0U };
int16_t iSpecificForceX_ { 0 };
int16_t iSpecificForceY_ { 0 };
int16_t iSpecificForceZ_ { 0 };
int16_t iAngularRateX_ { 0 };
int16_t iAngularRateY_ { 0 };
int16_t iAngularRateZ_ { 0 };
uint8_t uValidity_ { 0U };
};
/**
* @brief Payload of the time of inertial data message.
*/
struct STimeOfInertialData {
uint8_t uSequenceCounter_ { 0U };
uint8_t uInertialDataSequenceCounter_ { 0U };
uint64_t uTimestampUs_ { 0U };
};
/**
* @brief Navigation data message payload.
*/
struct SNavigationData {
uint8_t uSequenceCounter_ { 0U };
uint16_t uPressureHeight_ { 0 };
int16_t iVelocityDown_ { 0 };
int16_t iRoll_ { 0 };
int16_t iPitch_ { 0 };
uint16_t uMagneticHeading_ { 0U };
uint8_t uValidity_ { 0 };
};
/**
* @brief Payload of the "time of navigation data" message.
*/
struct STimeOfNavigationData {
uint8_t uSequenceCounter_ { 0U };
uint8_t uNavigationDataSequenceCounter_ { 0U };
uint64_t uTimestampUs_ { 0U };
};
/**
* @brief Accuracy message payload.
*/
struct SAccuracyData {
uint8_t uSequenceCounter_ { 0U };
uint16_t uAttitudeStdN_ { 0U };
uint16_t uAttitudeStdE_ { 0U };
uint16_t uMagneticHeadingStd_ { 0U };
uint64_t uTimestampUs_ { 0U };
};
/**
* @brief Payload of the "time of the latest pulse" message.
*/
struct STimeOfLatestSyncPulse {
uint8_t uSequenceCounter_ { 0U };
uint64_t uTimestampUs_ { 0U };
};
/**
* @brief Payload of the "software version" message.
*/
struct SSoftwareVersionData {
char acProjectCode_[3] { '\0', '\0', '\0' };
uint16_t uMajor_ { 0U };
uint16_t uMinor_ { 0U };
};
/**
* @brief Partial data of the "write to port event".
* The struct does not include a variable size array of data written to a port.
*/
struct SWriteToPortEventPartialData {
uint8_t uPortId_ { 0U };
uint64_t uTimestampUs_ { 0U };
uint16_t uDataLen_ { 0U };
};
/**
* @brief Debug information on runnable call.
*/
struct SRunnableCallEventData {
uint8_t uRunnableId_ { 0U };
uint64_t uTimestampUs_ { 0U };
};
/**
* @brief Inertial data message.
*/
struct SInertialDataMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eInertialData) };
SInertialData oInertialData_;
uint8_t auPadding_[PADDING_SIZE(SInertialData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Time of inertial data message.
*/
struct STimeOfInertialDataMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eTimeOfInertialData) };
STimeOfInertialData oTimeOfInertialData_;
uint8_t auPadding_[PADDING_SIZE(STimeOfInertialData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Navigation data message.
*/
struct SNavigationDataMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eNavigationData) };
SNavigationData oNavigationData_;
uint8_t auPadding_[PADDING_SIZE(SNavigationData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Navigation data accuracy message.
*/
struct SAccuracyDataMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eAccuracy) };
SAccuracyData oAccuracy_;
uint8_t auPadding_[PADDING_SIZE(SAccuracyData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Time of navigation data message.
*/
struct STimeOfNavigationDataMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eTimeOfNavigationData) };
STimeOfNavigationData oTimeOfNavigationData_;
uint8_t auPadding_[PADDING_SIZE(STimeOfNavigationData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Time of the latest sync pulse message.
*/
struct STimeOfLatestSyncPulseMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eTimeOfSyncPulse) };
STimeOfLatestSyncPulse oTimeOfLatestSyncPulse_;
uint8_t auPadding_[PADDING_SIZE(STimeOfLatestSyncPulse)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief Software version message.
*/
struct SSoftwareVersionMessage {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eSoftwareVersion) };
SSoftwareVersionData oSoftwareVersion_;
uint8_t auPadding_[PADDING_SIZE(SSoftwareVersionData)];
CrcType_t uCrc_ { 0U };
};
/**
* @brief A debug message with runnable call data.
*/
struct SRunnableCallEventDebugMessage {
SMessageHeader oHeader_{ CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eDebugEventRunnableCall) };
SRunnableCallEventData oRunnableCallData_;
uint8_t auPadding_[PADDING_SIZE(oRunnableCallData_)];
CrcType_t uCrc_{ 0U };
};
/**
* @brief Diagnostic Mode Messages
****************************************************************************/
/**
* @brief Diagnostic message: Page request from NVM.
*/
struct SPacketReadNVMPage {
SMessageHeader oHeader_;
uint8_t uPageNumber { 0U };
CrcType_t uCrc32 { 0U };
};
/**
* @brief Diagnostic message: confirmation of request processing by the device.
*/
struct SPacketReceiveConfirmation {
SMessageHeader oHeader_ { CSerialProtocol::uMarker1_,
CSerialProtocol::uMarker2_,
CSerialProtocol::uVersion_,
static_cast<uint8_t>(EMessageIds::eTypeAccept) };
EMessageIds eMessageType; // message type to confirm.
uint8_t uStatus { 0U }; // 0 - OK, other values - error codes
CrcType_t uCrc32 { 0U };
};
#pragma pack(pop)
};
@@ -0,0 +1,48 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file eulernav_bahrs_main.cpp
* A driver module for EULER-NAV Baro-Inertial AHRS.
*
* @author Fedor Baklanov <fedor.baklanov@euler-nav.com>
*/
#include <px4_platform_common/log.h>
#include "eulernav_driver.h"
extern "C" __EXPORT int eulernav_bahrs_main(int argc, char *argv[])
{
EulerNavDriver::main(argc, argv);
return OK;
}
@@ -0,0 +1,514 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "eulernav_driver.h"
#include <px4_platform_common/getopt.h>
#include <drivers/drv_sensor.h>
#include <matrix/Quaternion.hpp>
#include <matrix/Euler.hpp>
#include <atmosphere/atmosphere.h>
EulerNavDriver::EulerNavDriver(const char *device_name)
: ModuleParams{nullptr}
, _serial_port{device_name, 115200, ByteSize::EightBits, Parity::None, StopBits::One, FlowControl::Disabled}
, _data_buffer{}
, _px4_accel{DRV_INS_DEVTYPE_BAHRS}
, _px4_gyro{DRV_INS_DEVTYPE_BAHRS}
{
}
EulerNavDriver::~EulerNavDriver()
{
deinitialize();
}
int EulerNavDriver::task_spawn(int argc, char *argv[])
{
int task_id = px4_task_spawn_cmd("bahrs", SCHED_DEFAULT, SCHED_PRIORITY_FAST_DRIVER,
Config::TASK_STACK_SIZE, (px4_main_t)&run_trampoline, argv);
if (task_id < 0) {
_task_id = -1;
PX4_ERR("Failed to spawn task.");
} else {
_task_id = task_id;
}
return (_task_id < 0) ? 1 : 0;
}
EulerNavDriver *EulerNavDriver::instantiate(int argc, char *argv[])
{
int option_index = 1;
const char *option_arg{nullptr};
const char *device_name{nullptr};
while (true) {
int option{px4_getopt(argc, argv, "d:", &option_index, &option_arg)};
if (EOF == option) {
break;
}
switch (option) {
case 'd':
device_name = option_arg;
break;
default:
break;
}
}
auto *instance = new EulerNavDriver(device_name);
if (nullptr != instance) {
instance->initialize();
} else {
PX4_ERR("Failed to initialize EULER-NAV driver.");
}
return instance;
}
int EulerNavDriver::custom_command(int argc, char *argv[])
{
return print_usage("unrecognized command");
}
int EulerNavDriver::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Serial bus driver for the EULER-NAV Baro-Inertial AHRS.
### Examples
Attempt to start driver on a specified serial device.
$ eulernav_bahrs start -d /dev/ttyS1
Stop driver
$ eulernav_bahrs stop
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("eulernav_bahrs", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("ins");
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver");
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false);
PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print driver status");
PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver");
return PX4_OK;
}
int EulerNavDriver::print_status()
{
if (_is_initialized)
{
PX4_INFO("Elapsed time: %llu [us].\n", hrt_elapsed_time(&_statistics.start_time));
PX4_INFO("Total bytes received: %lu.\n", _statistics.total_bytes_received);
PX4_INFO("Inertial messages received: %lu. Navigation messages received: %lu.\n",
_statistics.inertial_message_counter, _statistics.navigation_message_counter);
PX4_INFO("Failed CRC count: %lu.\n", _statistics.crc_failures);
}
else
{
PX4_INFO("Initialization failed. The driver is not running.\n");
}
return PX4_OK;
}
void EulerNavDriver::run()
{
_statistics.start_time = hrt_absolute_time();
while(!should_exit())
{
if (_is_initialized)
{
const auto bytes_read{_serial_port.readAtLeast(_serial_read_buffer, sizeof(_serial_read_buffer),
Config::MIN_BYTES_TO_READ, Config::SERIAL_READ_TIMEOUT_MS)};
_statistics.total_bytes_received += bytes_read;
if (bytes_read > 0)
{
if (!_data_buffer.push_back(_serial_read_buffer, bytes_read))
{
PX4_ERR("No space in data buffer");
}
}
processDataBuffer();
}
else
{
// The driver failed to initialize in the instantiate() method, so we exit the loop.
request_stop();
}
}
}
void EulerNavDriver::initialize()
{
if (!_is_initialized)
{
if (_serial_port.open())
{
PX4_INFO("Serial port opened successfully.");
_is_initialized = true;
}
else
{
PX4_ERR("Failed to open serial port");
}
if (_is_initialized)
{
if (!_data_buffer.allocate(Config::DATA_BUFFER_SIZE))
{
PX4_ERR("Failed to allocate data buffer");
_is_initialized = false;
}
}
if (_is_initialized)
{
_attitude_pub.advertise();
_barometer_pub.advertise();
}
}
}
void EulerNavDriver::deinitialize()
{
if (_serial_port.isOpen())
{
_serial_port.close();
}
_data_buffer.deallocate();
_attitude_pub.unadvertise();
_barometer_pub.unadvertise();
_is_initialized = false;
}
void EulerNavDriver::processDataBuffer()
{
static_assert(Config::MIN_MESSAGE_LENGTH >= (sizeof(CSerialProtocol::SMessageHeader) + sizeof(CSerialProtocol::CrcType_t)));
using EMessageIds = CSerialProtocol::EMessageIds;
while (_data_buffer.space_used() >= Config::MIN_MESSAGE_LENGTH)
{
if (!_next_message_info.is_detected)
{
_next_message_info.is_detected = findNextMessageHeader(_data_buffer);
if (!_next_message_info.is_detected)
{
// No message header found, wait for more bytes to arrive.
break;
}
if (!retrieveProtocolVersionAndMessageType(_data_buffer, _next_message_info.protocol_version, _next_message_info.message_code))
{
_next_message_info.is_detected = false;
}
}
if (_next_message_info.is_detected)
{
static_assert(sizeof(CSerialProtocol::SMessageHeader) < Config::MIN_MESSAGE_LENGTH);
const EMessageIds message_id{static_cast<EMessageIds>(_next_message_info.message_code)};
const int32_t message_length{getMessageLength(message_id)};
if ((message_length < 0) || (message_length < Config::MIN_MESSAGE_LENGTH) ||
(message_length > static_cast<int32_t>(sizeof(_message_storage))) || ((message_length % sizeof(uint32_t)) != 0U))
{
// The message is unknown, not supported, or does not fit into the temporary storage.
_next_message_info.is_detected = false;
continue;
}
const int32_t bytes_to_retrieve{message_length - static_cast<int32_t>(sizeof(CSerialProtocol::SMessageHeader))};
if (static_cast<int32_t>(_data_buffer.space_used()) < bytes_to_retrieve)
{
// Do nothing and wait for more bytes to arrive.
break;
}
// Get message from the data buffer
uint8_t* bytes{reinterpret_cast<uint8_t*>(_message_storage)};
bytes[0] = CSerialProtocol::uMarker1_;
bytes[1] = CSerialProtocol::uMarker2_;
bytes[2] = reinterpret_cast<uint8_t*>(&_next_message_info.protocol_version)[0];
bytes[3] = reinterpret_cast<uint8_t*>(&_next_message_info.protocol_version)[1];
bytes[4] = _next_message_info.message_code;
if (static_cast<size_t>(bytes_to_retrieve) == _data_buffer.pop_front(bytes + sizeof(CSerialProtocol::SMessageHeader), bytes_to_retrieve))
{
const uint32_t message_length_in_words{message_length / sizeof(uint32_t)};
const uint32_t actual_crc{crc32(_message_storage, message_length_in_words - 1)};
const uint32_t expected_crc = _message_storage[message_length_in_words - 1];
if (expected_crc != actual_crc)
{
++_statistics.crc_failures;
}
else
{
decodeMessageAndPublishData(bytes, message_id);
}
}
_next_message_info.is_detected = false;
}
}
}
bool EulerNavDriver::findNextMessageHeader(Ringbuffer& buffer)
{
bool result{false};
while (buffer.space_used() >= sizeof(CSerialProtocol::SMessageHeader))
{
uint8_t sync_byte{0U};
if ((1 == buffer.pop_front(&sync_byte, 1)) && (CSerialProtocol::uMarker1_ == sync_byte))
{
sync_byte = 0U;
if ((1 == buffer.pop_front(&sync_byte, 1)) && (CSerialProtocol::uMarker2_ == sync_byte))
{
result = true;
break;
}
}
}
return result;
}
bool EulerNavDriver::retrieveProtocolVersionAndMessageType(Ringbuffer& buffer, uint16_t& protocol_ver, uint8_t& message_code)
{
bool status{true};
auto bytes_to_pop{sizeof(protocol_ver)};
// Note: BAHRS uses little endian
if (bytes_to_pop != buffer.pop_front(reinterpret_cast<uint8_t*>(&protocol_ver), bytes_to_pop))
{
status = false;
}
if (status)
{
bytes_to_pop = 1;
if (bytes_to_pop != buffer.pop_front(&message_code, bytes_to_pop))
{
status = false;
}
}
return status;
}
void EulerNavDriver::decodeMessageAndPublishData(const uint8_t* data, CSerialProtocol::EMessageIds messsage_id)
{
switch (messsage_id)
{
case CSerialProtocol::EMessageIds::eInertialData:
handleInertialDataMessage(data);
break;
case CSerialProtocol::EMessageIds::eNavigationData:
handleNavigationDataMessage(data);
break;
default:
break;
}
}
void EulerNavDriver::handleInertialDataMessage(const uint8_t* data)
{
const CSerialProtocol::SInertialDataMessage* imu_msg{reinterpret_cast<const CSerialProtocol::SInertialDataMessage*>(data)};
if (nullptr != imu_msg)
{
const auto& imu_data{imu_msg->oInertialData_};
const bool accel_valid{((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_X) > 0) &&
((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_Y) > 0) &&
((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_Z) > 0)};
const bool gyro_valid{((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_X) > 0) &&
((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_Y) > 0) &&
((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_Z) > 0)};
const auto time = hrt_absolute_time();
if (accel_valid)
{
const float accel_x{CSerialProtocol::skfSpecificForceScale_ * static_cast<float>(imu_data.iSpecificForceX_)};
const float accel_y{CSerialProtocol::skfSpecificForceScale_ * static_cast<float>(imu_data.iSpecificForceY_)};
const float accel_z{CSerialProtocol::skfSpecificForceScale_ * static_cast<float>(imu_data.iSpecificForceZ_)};
_px4_accel.update(time, accel_x, accel_y, accel_z);
}
if (gyro_valid)
{
const float gyro_x{CSerialProtocol::skfAngularRateScale_ * static_cast<float>(imu_data.iAngularRateX_)};
const float gyro_y{CSerialProtocol::skfAngularRateScale_ * static_cast<float>(imu_data.iAngularRateY_)};
const float gyro_z{CSerialProtocol::skfAngularRateScale_ * static_cast<float>(imu_data.iAngularRateZ_)};
_px4_gyro.update(time, gyro_x, gyro_y, gyro_z);
}
++_statistics.inertial_message_counter;
}
}
void EulerNavDriver::handleNavigationDataMessage(const uint8_t* data)
{
const CSerialProtocol::SNavigationDataMessage* nav_msg{reinterpret_cast<const CSerialProtocol::SNavigationDataMessage*>(data)};
if (nullptr != nav_msg)
{
const auto& nav_data{nav_msg->oNavigationData_};
const bool roll_valid{(nav_data.uValidity_ & BIT_VALID_ROLL) > 0};
const bool pitch_valid{(nav_data.uValidity_ & BIT_VALID_PITCH) > 0};
const bool yaw_valid{(nav_data.uValidity_ & BIT_VALID_MAGNETIC_HEADING) > 0};
const auto time{hrt_absolute_time()};
if (roll_valid && pitch_valid && yaw_valid)
{
const float roll{CSerialProtocol::skfAngleScale_ * static_cast<float>(nav_data.iRoll_)};
const float pitch{CSerialProtocol::skfAngleScale_ * static_cast<float>(nav_data.iPitch_)};
const float yaw{CSerialProtocol::skfAngleScale_ * static_cast<float>(nav_data.uMagneticHeading_)};
const matrix::Quaternionf quat{matrix::Eulerf{roll, pitch, yaw}};
px4::msg::VehicleAttitude attitude{};
attitude.q[0] = quat(0);
attitude.q[1] = quat(1);
attitude.q[2] = quat(2);
attitude.q[3] = quat(3);
attitude.timestamp = time;
attitude.timestamp_sample = time;
_attitude_pub.publish(attitude);
}
const bool height_valid{(nav_data.uValidity_ & BIT_VALID_HEIGHT) > 0};
if (height_valid)
{
const float height{(CSerialProtocol::skfHeightScale_ * static_cast<float>(nav_data.uPressureHeight_)) - CSerialProtocol::skfHeighOffset_};
px4::msg::SensorBaro pressure{};
pressure.pressure = atmosphere::getPressureFromAltitude(height);
// EULER-NAV Baro-Inertial AHRS provides height estimate from a Kalman filter. It has got low noise and resolution
// of about 17 cm. It causes PX4 autopilot to mistakenly report that pressure signal is stale. In order to prevent
// the false alarms we add a small noise to the received height data.
if (_statistics.navigation_message_counter % 2U == 0)
{
pressure.pressure += 0.01F;
}
pressure.timestamp = time;
pressure.timestamp_sample = time;
pressure.device_id = DRV_INS_DEVTYPE_BAHRS;
pressure.temperature = NAN;
_barometer_pub.publish(pressure);
}
++_statistics.navigation_message_counter;
}
}
int32_t EulerNavDriver::getMessageLength(CSerialProtocol::EMessageIds messsage_id)
{
int message_length{-1};
switch (messsage_id)
{
case CSerialProtocol::EMessageIds::eInertialData:
message_length = sizeof(CSerialProtocol::SInertialDataMessage);
break;
case CSerialProtocol::EMessageIds::eNavigationData:
message_length = sizeof(CSerialProtocol::SNavigationDataMessage);
break;
default:
break;
}
return message_length;
}
uint32_t EulerNavDriver::crc32(const uint32_t* buffer, size_t length)
{
uint32_t crc = 0xFFFFFFFF;
for (size_t i = 0; i < length; ++i)
{
crc = crc ^ buffer[i];
for (uint8_t j = 0; j < 32; j++)
{
if (crc & 0x80000000)
{
crc = (crc << 1) ^ 0x04C11DB7;
}
else
{
crc = (crc << 1);
}
}
}
return crc;
}
@@ -0,0 +1,174 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/Serial.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/vehicle_attitude.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <uORB/topics/sensor_baro.h>
#include <Ringbuffer.hpp>
#include <containers/Array.hpp>
#include "CSerialProtocol.h"
class EulerNavDriver : public ModuleBase<EulerNavDriver>, public ModuleParams
{
public:
/// @brief Class constructor
/// @param device_name Serial port to open
EulerNavDriver(const char *device_name);
~EulerNavDriver();
/// @brief Required by ModuleBase
static int task_spawn(int argc, char *argv[]);
/// @brief Required by ModuleBase
static EulerNavDriver *instantiate(int argc, char *argv[]);
/// @brief Required by ModuleBase
static int custom_command(int argc, char *argv[]);
/// @brief Required by ModuleBase
static int print_usage(const char *reason = nullptr);
/// @brief Overload of the method from the ModuleBase
int print_status() final;
/// @brief The main loop of the task.
void run() final;
private:
/// @brief Driver performance indicators
class Statistics
{
public:
uint32_t total_bytes_received{0U}; ///< Total number of received bytes
uint32_t inertial_message_counter{0U}; ///< Total number of received inertial data messages
uint32_t navigation_message_counter{0U}; ///< Total number of received navigation messages
uint32_t crc_failures{0U}; ///< CRC failure counter
hrt_abstime start_time{0U}; ///< Driver start time, [us]
};
/// @brief Configuration constants
class Config
{
public:
static constexpr uint32_t TASK_STACK_SIZE{2048}; ///< Driver task stack size
static constexpr uint32_t SERIAL_READ_BUFFER_SIZE{128}; ///< Buffer size for serial port read operations
static constexpr uint32_t MIN_BYTES_TO_READ{16}; ///< Minimum number of bytes to wait for when reading from a serial port
static constexpr uint32_t SERIAL_READ_TIMEOUT_MS{5}; ///< A timeout for serial port read operation
static constexpr uint32_t DATA_BUFFER_SIZE{512}; ///< Size of a ring buffer for storing RX data stream
static constexpr int32_t MIN_MESSAGE_LENGTH{12}; ///< Min length of a valid message. 5 bytes header + 4 bytes CRC + padding to 12 (multiple of 32 bit words)
};
/// @brief An object for grouping message-related attributes
class NextMessageInfo
{
public:
bool is_detected{false}; ///< A flag to indicate that the next message header was detected
uint16_t protocol_version{0U}; ///< Protocol version retrieved from the next message header
uint8_t message_code{0U}; ///< Message code retrieved from the next message header
};
/// @brief Perform initialization
/// If the driver is not initialized, the function does the following:
/// 1. Opens serial port
/// 2. Allocates a ring buffer for RX data stream
/// 3. Cleans up if any of the previous operations fails
/// 4. Sets the "is initialized" flag to true on success
void initialize();
/// @brief De-initialize
/// The function does the following:
/// 1. Close the serial port, if it is opened
/// 2. Deallocates the ring buffer
/// 3. Resets the "is initialized" flag to false
void deinitialize();
/// @brief Process data in the ring buffer.
/// Extracts and parses protocol messages.
void processDataBuffer();
/// @brief Searches the ring buffer for sync bytes.
/// @param buffer Ring buffer to search
/// @return True if sync bytes found, false if the number of bytes remaining in the buffer is less then message header length.
static bool findNextMessageHeader(Ringbuffer &buffer);
/// @brief Get protocol version and message code from the ring buffer.
/// @param buffer The buffer to process
/// @param protocol_ver Output protocol version
/// @param message_code Output message code
/// @return True on success, false on failure
static bool retrieveProtocolVersionAndMessageType(Ringbuffer &buffer, uint16_t &protocol_ver, uint8_t &message_code);
/// @brief Decode a message from BAHRS and publish its content.
/// @param data An array of message bytes
/// @param messsage_id Message ID
void decodeMessageAndPublishData(const uint8_t *data, CSerialProtocol::EMessageIds messsage_id);
/// @brief Decode and publish IMU data.
/// @param data Inertial message data bytes
void handleInertialDataMessage(const uint8_t *data);
/// @brief Decode and publish vehicle attitude and pressure height.
/// @param data Navigation message data bytes
void handleNavigationDataMessage(const uint8_t *data);
/// @brief Get message length by message ID
/// @param messsage_id Query message ID
/// @return Message length, or -1 if the message ID is unknown or not supported.
static int32_t getMessageLength(CSerialProtocol::EMessageIds messsage_id);
/// @brief Perform CRC
/// @param buf Data buffer pointer
/// @param len Number of words to include in the CRC.
/// @return CRC value
static uint32_t crc32(const uint32_t *buf, size_t len);
device::Serial _serial_port; ///< Serial port object to read data from
Ringbuffer _data_buffer; ///< A buffer for RX data stream
uint8_t _serial_read_buffer[Config::SERIAL_READ_BUFFER_SIZE]; ///< A buffer for serial port read operation
uint32_t _message_storage[8]; ///< A temporary storage for BAHRS messages being extracted
NextMessageInfo _next_message_info{}; ///< Attributes of the next message detected in the data buffer
Statistics _statistics{}; ///< Driver performance indicators
bool _is_initialized{false}; ///< Initialization flag
PX4Accelerometer _px4_accel; ///< Accelerometer sensor object for publishing acceleration data
PX4Gyroscope _px4_gyro; ///< Gyroscope sensor object for publishing angular rate data
uORB::PublicationMulti<px4::msg::VehicleAttitude> _attitude_pub{ORB_ID(vehicle_attitude)}; ///< Vehicle attitude publisher
uORB::PublicationMulti<px4::msg::SensorBaro> _barometer_pub{ORB_ID(sensor_baro)}; ///< Pressure data publisher
};
@@ -0,0 +1,7 @@
module_name: EULER-NAV BAHRS
serial_config:
- command: eulernav_bahrs start -d ${SERIAL_DEV}
port_config_param:
name: SENS_BAHRS_CFG
group: Sensors
+10
View File
@@ -19,6 +19,16 @@ actuator_output:
parameters:
- group: Actuator Outputs
definitions:
PCA9685_EN_BUS:
description:
short: Enable the PCA9685 output driver
long: |
Enable the PCA9685 output driver.
The integer refers to the I2C bus number where PCA9685 is connected.
type: int32
min: 0
max: 10
default: 0
PCA9685_SCHD_HZ:
description:
short: PWM update rate
+1 -1
View File
@@ -96,7 +96,7 @@ UavcanEscController::update_outputs(uint16_t outputs[MAX_ACTUATORS], unsigned to
_prev_cmd_pub = timestamp;
uavcan::equipment::esc::RawCommand msg;
uavcan::equipment::esc::RawCommand msg = {};
// directly output values from mixer
for (unsigned i = 0; i < total_outputs; i++) {
@@ -644,7 +644,7 @@ uavcan::int16_t CanIface::configureFilters(const uavcan::CanFilterConfig *filter
bool CanIface::waitCCCRBitStateChange(uint32_t mask, bool target_state)
{
#if UAVCAN_STM32_NUTTX
#if UAVCAN_STM32H7_NUTTX
const unsigned Timeout = 1000;
#else
const unsigned Timeout = 2000000;
@@ -657,7 +657,7 @@ bool CanIface::waitCCCRBitStateChange(uint32_t mask, bool target_state)
return true;
}
#if UAVCAN_STM32_NUTTX
#if UAVCAN_STM32H7_NUTTX
::usleep(1000);
#endif
}
+6
View File
@@ -505,12 +505,16 @@ void UavcanNode::Run()
if (can_init_res < 0) {
PX4_ERR("CAN driver init failed %i", can_init_res);
ScheduleClear();
return;
}
int rv = _node.start();
if (rv < 0) {
PX4_ERR("Failed to start the node");
ScheduleClear();
return;
}
// If the node_id was not supplied by the bootloader do Dynamic Node ID allocation
@@ -528,6 +532,8 @@ void UavcanNode::Run()
if (client_start_res < 0) {
PX4_ERR("Failed to start the dynamic node ID client");
ScheduleClear();
return;
}
}
}
+1 -1
View File
@@ -67,11 +67,11 @@ add_subdirectory(pure_pursuit EXCLUDE_FROM_ALL)
add_subdirectory(rate_control EXCLUDE_FROM_ALL)
add_subdirectory(rc EXCLUDE_FROM_ALL)
add_subdirectory(ringbuffer EXCLUDE_FROM_ALL)
add_subdirectory(rover_control EXCLUDE_FROM_ALL)
add_subdirectory(rtl EXCLUDE_FROM_ALL)
add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL)
add_subdirectory(slew_rate EXCLUDE_FROM_ALL)
add_subdirectory(stick_yaw EXCLUDE_FROM_ALL)
add_subdirectory(surface_vehicle_control EXCLUDE_FROM_ALL)
add_subdirectory(systemlib EXCLUDE_FROM_ALL)
add_subdirectory(system_identification EXCLUDE_FROM_ALL)
add_subdirectory(tecs EXCLUDE_FROM_ALL)
+13
View File
@@ -150,5 +150,18 @@ param_modify_on_import_ret param_modify_on_import(bson_node_t node)
}
}
// 2025-08-22: translate SDLOG_MODE (disabled) to SDLOG_BACKEND (no logging backend)
{
if (strcmp("SDLOG_MODE", node->name) == 0) {
if (node->i32 == -1) {
node->i32 = 0;
int32_t sdlog_backend_val = 0;
param_set(param_find("SDLOG_BACKEND"), &sdlog_backend_val);
PX4_INFO("migrating %s -> %s", "SDLOG_MODE", "SDLOG_BACKEND");
}
}
}
return param_modify_on_import_ret::PARAM_NOT_MODIFIED;
}
+1 -1
View File
@@ -55,7 +55,7 @@ RtlTimeEstimator::RtlTimeEstimator() : ModuleParams(nullptr)
_param_fw_sink_rate = param_find("FW_T_SINK_R_SP");
_param_fw_airspeed_trim = param_find("FW_AIRSPD_TRIM");
_param_mpc_xy_cruise = param_find("MPC_XY_CRUISE");
_param_rover_cruise_speed = param_find("RO_SPEED_LIM");
_param_rover_cruise_speed = param_find("SV_SPEED_LIM");
};
rtl_time_estimate_s RtlTimeEstimator::getEstimate() const
@@ -31,11 +31,11 @@
#
############################################################################
px4_add_library(rover_control
RoverControl.cpp
RoverControl.hpp
px4_add_library(surface_vehicle_control
SurfaceVehicleControl.cpp
SurfaceVehicleControl.hpp
)
target_link_libraries(rover_control PUBLIC PID)
target_link_libraries(rover_control PUBLIC geo)
px4_add_unit_gtest(SRC RoverControlTest.cpp LINKLIBS rover_control)
target_link_libraries(surface_vehicle_control PUBLIC PID)
target_link_libraries(surface_vehicle_control PUBLIC geo)
px4_add_unit_gtest(SRC SurfaceVehicleControlTest.cpp LINKLIBS surface_vehicle_control)
@@ -31,9 +31,9 @@
*
****************************************************************************/
#include "RoverControl.hpp"
#include "SurfaceVehicleControl.hpp"
using namespace matrix;
namespace RoverControl
namespace SurfaceVehicleControl
{
float throttleControl(SlewRate<float> &motor_setpoint, const float throttle_setpoint,
const float current_motor_setpoint, const float max_accel, const float max_decel, const float max_thr_spd,
@@ -265,4 +265,4 @@ float calcWaypointTransitionAngle(Vector2f &prev_wp_ned, Vector2f &curr_wp_ned,
return acosf(cosin);
}
} // RoverControl
} // SurfaceVehicleControl
@@ -32,10 +32,10 @@
****************************************************************************/
/**
* @file RoverControl.hpp
* @file SurfaceVehicleControl.hpp
*
* Functions that are shared among the different rover modules.
* Also includes the parameters that are shared among the rover modules.
* Functions that are shared among the different surface vehicles.
* Also includes the parameters that are shared among them.
*/
#pragma once
@@ -47,7 +47,7 @@
#include <lib/geo/geo.h>
using namespace matrix;
namespace RoverControl
namespace SurfaceVehicleControl
{
/**
* Applies acceleration/deceleration slew rate to a throttle setpoint.
@@ -56,7 +56,7 @@ namespace RoverControl
* @param current_motor_setpoint Currently applied motor input [-1, 1]
* @param max_accel Maximum allowed acceleration [m/s^2]
* @param max_decel Maximum allowed deceleration [m/s^2]
* @param max_thr_spd Speed the rover drives at maximum throttle [m/s]
* @param max_thr_spd Speed the vehicle drives at maximum throttle [m/s]
* @param dt Time since last update [s]
* @return Motor Setpoint [-1, 1]
*/
@@ -76,6 +76,7 @@ float throttleControl(SlewRate<float> &motor_setpoint, float throttle_setpoint,
*/
float attitudeControl(SlewRateYaw<float> &adjusted_yaw_setpoint, PID &pid_yaw, float yaw_slew_rate,
float vehicle_yaw, float yaw_setpoint, float dt);
/**
* Applies acceleration/deceleration slew rate to a speed setpoint and calculates the necessary throttle setpoint
* using a feed forward term and PID controller.
@@ -95,7 +96,7 @@ float speedControl(SlewRate<float> &speed_with_rate_limit, PID &pid_speed, float
/**
* Applies yaw acceleration slew rate to a yaw rate setpoint and calculates the necessary speed diff setpoint
* using a feedforward term and/or a PID controller.
* Note: This function is only for rovers that control the rate through a speed difference between the left/right wheels.
* Note: This function is only for vehicles that control the rate through a speed difference between the left/right wheels.
* @param adjusted_yaw_rate_setpoint Yaw rate setpoint with applied slew rate [-1, 1] (Updated by this function).
* @param pid_yaw_rate Yaw rate PID (Updated by this function).
* @param yaw_rate_setpoint Yaw rate setpoint [rad/s].
@@ -119,7 +120,7 @@ float rateControl(SlewRate<float> &adjusted_yaw_rate_setpoint, PID &pid_yaw_rate
* @param prev_wp_ned Previous waypoint in NED frame (Updated by this function)
* @param next_wp_ned Next waypoint in NED frame (Updated by this function)
* @param position_setpoint_triplet Position Setpoint Triplet
* @param curr_pos Current position of the rover in global frame
* @param curr_pos Current position of the vehicle in global frame
* @param global_ned_proj_ref Global to ned projection
*/
void globalToLocalSetpointTriplet(Vector2f &curr_wp_ned, Vector2f &prev_wp_ned, Vector2f &next_wp_ned,
@@ -33,24 +33,24 @@
/******************************************************************
* Test code for the Pure Pursuit algorithm
* Run this test only using "make tests TESTFILTER=RoverControl"
* Run this test only using "make tests TESTFILTER=SurfaceVehicleControl"
******************************************************************/
#include <gtest/gtest.h>
#include "RoverControl.hpp"
#include "SurfaceVehicleControl.hpp"
TEST(calcWaypointTransitionAngle, invalidInputs)
{
Vector2f prev_wp_ned(NAN, NAN);
Vector2f curr_wp_ned(10.f, 10.f);
Vector2f next_wp_ned(10.f, 10.f);
float prevInvalid = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
float prevInvalid = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
prev_wp_ned = Vector2f(10.f, 10.f);
curr_wp_ned = Vector2f(NAN, NAN);
float currInvalid = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
float currInvalid = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
curr_wp_ned = Vector2f(10.f, 10.f);
next_wp_ned = Vector2f(NAN, NAN);
float nextInvalid = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
float nextInvalid = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FALSE(PX4_ISFINITE(prevInvalid));
EXPECT_FALSE(PX4_ISFINITE(currInvalid));
EXPECT_FALSE(PX4_ISFINITE(nextInvalid));
@@ -63,7 +63,7 @@ TEST(calcWaypointTransitionAngle, validInputs)
Vector2f prev_wp_ned(0.f, 0.f);
Vector2f curr_wp_ned(10.f, 0.f);
Vector2f next_wp_ned(20.f, 0.f);
const float angle1 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle1 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FLOAT_EQ(angle1, M_PI_F);
/**
@@ -74,7 +74,7 @@ TEST(calcWaypointTransitionAngle, validInputs)
prev_wp_ned = Vector2f(0.f, 0.f);
curr_wp_ned = Vector2f(10.f, 0.f);
next_wp_ned = Vector2f(20.f, 10.f);
const float angle2 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle2 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FLOAT_EQ(angle2, M_PI_F - M_PI_4_F);
/**
@@ -85,7 +85,7 @@ TEST(calcWaypointTransitionAngle, validInputs)
prev_wp_ned = Vector2f(0.f, 0.f);
curr_wp_ned = Vector2f(10.f, 0.f);
next_wp_ned = Vector2f(10.f, 10.f);
const float angle3 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle3 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FLOAT_EQ(angle3, M_PI_2_F);
/**
@@ -96,20 +96,20 @@ TEST(calcWaypointTransitionAngle, validInputs)
prev_wp_ned = Vector2f(0.f, 0.f);
curr_wp_ned = Vector2f(10.f, 0.f);
next_wp_ned = Vector2f(0.f, 10.f);
const float angle4 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle4 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FLOAT_EQ(angle4, M_PI_4_F);
// P/C -- N
prev_wp_ned = Vector2f(0.f, 0.f);
curr_wp_ned = Vector2f(0.f, 0.f);
next_wp_ned = Vector2f(10.f, 0.f);
const float angle5 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle5 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FALSE(PX4_ISFINITE(angle5));
// P -- C/N
prev_wp_ned = Vector2f(0.f, 0.f);
curr_wp_ned = Vector2f(10.f, 0.f);
next_wp_ned = Vector2f(10.f, 0.f);
const float angle6 = RoverControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
const float angle6 = SurfaceVehicleControl::calcWaypointTransitionAngle(prev_wp_ned, curr_wp_ned, next_wp_ned);
EXPECT_FALSE(PX4_ISFINITE(angle6));
}
@@ -32,9 +32,9 @@
****************************************************************************/
/**
* @file rovercontrol_params.c
* @file surface_vehicle_params.c
*
* Parameters defined by the rover control lib.
* Parameters defined by the surface vehicle control lib.
*/
/**
@@ -46,9 +46,9 @@
* @max 1
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_STICK_DZ, 0.1f);
PARAM_DEFINE_FLOAT(SV_YAW_STICK_DZ, 0.1f);
/**
* Yaw rate expo factor
@@ -61,14 +61,14 @@ PARAM_DEFINE_FLOAT(RO_YAW_STICK_DZ, 0.1f);
* @min 0
* @max 1
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_EXPO, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_EXPO, 0.f);
/**
* Yaw rate super expo factor
*
* "Superexponential" factor for refining the input curve shape tuned using RO_YAW_EXPO.
* "Superexponential" factor for refining the input curve shape tuned using SV_YAW_EXPO.
*
* 0 Pure Expo function
* 0.7 reasonable shape enhancement for intuitive stick feel
@@ -77,9 +77,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_EXPO, 0.f);
* @min 0
* @max 0.95
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_SUPEXPO, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_SUPEXPO, 0.f);
/**
* Yaw rate measurement threshold
@@ -91,9 +91,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_SUPEXPO, 0.f);
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_RATE_TH, 3.f);
PARAM_DEFINE_FLOAT(SV_YAW_RATE_TH, 3.f);
/**
* Proportional gain for closed loop yaw rate controller
@@ -102,9 +102,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_RATE_TH, 3.f);
* @max 100
* @increment 0.01
* @decimal 3
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_RATE_P, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_RATE_P, 0.f);
/**
* Integral gain for closed loop yaw rate controller
@@ -113,9 +113,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_RATE_P, 0.f);
* @max 100
* @increment 0.01
* @decimal 3
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_RATE_I, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_RATE_I, 0.f);
/**
* Yaw rate limit
@@ -128,9 +128,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_RATE_I, 0.f);
* @max 10000
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_RATE_LIM, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_RATE_LIM, 0.f);
/**
* Yaw acceleration limit
@@ -143,9 +143,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_RATE_LIM, 0.f);
* @max 10000
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_ACCEL_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_YAW_ACCEL_LIM, -1.f);
/**
* Yaw deceleration limit
@@ -158,9 +158,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_ACCEL_LIM, -1.f);
* @max 10000
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_DECEL_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_YAW_DECEL_LIM, -1.f);
/**
* Yaw rate correction factor
@@ -174,9 +174,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_DECEL_LIM, -1.f);
* @max 10000
* @increment 0.01
* @decimal 2
* @group Rover Rate Control
* @group SV Rate Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_RATE_CORR, 1.f);
PARAM_DEFINE_FLOAT(SV_YAW_RATE_CORR, 1.f);
/**
* Proportional gain for closed loop yaw controller
@@ -185,12 +185,12 @@ PARAM_DEFINE_FLOAT(RO_YAW_RATE_CORR, 1.f);
* @max 100
* @increment 0.01
* @decimal 3
* @group Rover Attitude Control
* @group SV Attitude Control
*/
PARAM_DEFINE_FLOAT(RO_YAW_P, 0.f);
PARAM_DEFINE_FLOAT(SV_YAW_P, 0.f);
/**
* Speed the rover drives at maximum throttle
* Speed the vehicle drives at maximum throttle
*
* Used to linearly map speeds [m/s] to throttle values [-1. 1].
*
@@ -199,9 +199,9 @@ PARAM_DEFINE_FLOAT(RO_YAW_P, 0.f);
* @unit m/s
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_MAX_THR_SPEED, 0.f);
PARAM_DEFINE_FLOAT(SV_MAX_THR_SPEED, 0.f);
/**
* Proportional gain for ground speed controller
@@ -210,9 +210,9 @@ PARAM_DEFINE_FLOAT(RO_MAX_THR_SPEED, 0.f);
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_SPEED_P, 0.f);
PARAM_DEFINE_FLOAT(SV_SPEED_P, 0.f);
/**
* Integral gain for ground speed controller
@@ -221,9 +221,9 @@ PARAM_DEFINE_FLOAT(RO_SPEED_P, 0.f);
* @max 100
* @increment 0.001
* @decimal 3
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_SPEED_I, 0.f);
PARAM_DEFINE_FLOAT(SV_SPEED_I, 0.f);
/**
* Speed limit
@@ -235,56 +235,56 @@ PARAM_DEFINE_FLOAT(RO_SPEED_I, 0.f);
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_SPEED_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_SPEED_LIM, -1.f);
/**
* Acceleration limit
*
* Set to -1 to disable.
* For mecanum rovers this limit is used for longitudinal and lateral acceleration.
* For omnidirectional vehicles this limit is used for longitudinal and lateral acceleration.
*
* @unit m/s^2
* @min -1
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_ACCEL_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_ACCEL_LIM, -1.f);
/**
* Deceleration limit
*
* Set to -1 to disable.
* Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
* For mecanum rovers this limit is used for longitudinal and lateral deceleration.
* Note that if it is disabled the vehicle will not slow down when approaching waypoints in auto modes.
* For omnidirectional vehicles this limit is used for longitudinal and lateral deceleration.
*
* @unit m/s^2
* @min -1
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_DECEL_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_DECEL_LIM, -1.f);
/**
* Jerk limit
*
* Set to -1 to disable.
* Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
* For mecanum rovers this limit is used for longitudinal and lateral jerk.
* Note that if it is disabled the vehicle will not slow down when approaching waypoints in auto modes.
* For omnidirectional vehicles this limit is used for longitudinal and lateral jerk.
*
* @unit m/s^3
* @min -1
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_JERK_LIM, -1.f);
PARAM_DEFINE_FLOAT(SV_JERK_LIM, -1.f);
/**
* Speed measurement threshold
@@ -297,14 +297,14 @@ PARAM_DEFINE_FLOAT(RO_JERK_LIM, -1.f);
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_SPEED_TH, 0.1f);
PARAM_DEFINE_FLOAT(SV_SPEED_TH, 0.1f);
/**
* Tuning parameter for the speed reduction based on the course error
*
* Reduced_speed = RO_MAX_THR_SPEED * (1 - normalized_course_error * RO_SPEED_RED)
* Reduced_speed = SV_MAX_THR_SPEED * (1 - normalized_course_error * SV_SPEED_RED)
* The normalized course error is the angle between the current course and the bearing setpoint
* interpolated from [0, 180] -> [0, 1].
* Higher value -> More speed reduction.
@@ -315,6 +315,6 @@ PARAM_DEFINE_FLOAT(RO_SPEED_TH, 0.1f);
* @max 100
* @increment 0.01
* @decimal 2
* @group Rover Velocity Control
* @group SV Speed Control
*/
PARAM_DEFINE_FLOAT(RO_SPEED_RED, -1.f);
PARAM_DEFINE_FLOAT(SV_SPEED_RED, -1.f);
+241
View File
@@ -0,0 +1,241 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudder.hpp"
using namespace time_literals;
BoatRudder::BoatRudder() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl)
{
updateParams();
}
bool BoatRudder::init()
{
ScheduleOnInterval(10_ms); // 100 Hz
return true;
}
void BoatRudder::updateParams()
{
ModuleParams::updateParams();
}
void BoatRudder::Run()
{
if (_parameter_update_sub.updated()) {
parameter_update_s param_update{};
_parameter_update_sub.copy(&param_update);
updateParams();
runSanityChecks();
}
if (_vehicle_control_mode_sub.updated()) {
vehicle_control_mode_s vehicle_control_mode{};
_vehicle_control_mode_sub.copy(&vehicle_control_mode);
// Run sanity checks if the control mode changes (Note: This has to be done this way, because the topic is periodically updated at 2 Hz)
if (_vehicle_control_mode.flag_control_position_enabled != vehicle_control_mode.flag_control_position_enabled ||
_vehicle_control_mode.flag_control_velocity_enabled != vehicle_control_mode.flag_control_velocity_enabled ||
_vehicle_control_mode.flag_control_attitude_enabled != vehicle_control_mode.flag_control_attitude_enabled ||
_vehicle_control_mode.flag_control_rates_enabled != vehicle_control_mode.flag_control_rates_enabled ||
_vehicle_control_mode.flag_control_allocation_enabled != vehicle_control_mode.flag_control_allocation_enabled) {
_vehicle_control_mode = vehicle_control_mode;
runSanityChecks();
reset();
} else {
_vehicle_control_mode = vehicle_control_mode;
}
}
if (_vehicle_control_mode.flag_armed && _sanity_checks_passed) {
_was_armed = true;
generateSetpoints();
updateControllers();
} else if (_was_armed) { // Reset all controllers and stop the vehicle
reset();
_boat_rudder_act_control.stopVehicle();
_was_armed = false;
}
}
void BoatRudder::generateSetpoints()
{
vehicle_status_s vehicle_status{};
_vehicle_status_sub.copy(&vehicle_status);
switch (vehicle_status.nav_state) {
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
_boat_rudder_auto_mode.autoControl();
break;
case vehicle_status_s::NAVIGATION_STATE_OFFBOARD:
_boat_rudder_offboard_mode.offboardControl();
break;
case vehicle_status_s::NAVIGATION_STATE_MANUAL:
_boat_rudder_manual_mode.manual();
break;
case vehicle_status_s::NAVIGATION_STATE_ACRO:
_boat_rudder_manual_mode.acro();
break;
case vehicle_status_s::NAVIGATION_STATE_STAB:
_boat_rudder_manual_mode.stab();
break;
case vehicle_status_s::NAVIGATION_STATE_POSCTL:
_boat_rudder_manual_mode.position();
break;
default:
break;
}
}
void BoatRudder::updateControllers()
{
if (_vehicle_control_mode.flag_control_position_enabled) {
_boat_rudder_pos_control.updatePosControl();
}
if (_vehicle_control_mode.flag_control_velocity_enabled) {
_boat_rudder_speed_control.updateSpeedControl();
}
if (_vehicle_control_mode.flag_control_attitude_enabled) {
_boat_rudder_att_control.updateAttControl();
}
if (_vehicle_control_mode.flag_control_rates_enabled) {
_boat_rudder_rate_control.updateRateControl();
}
if (_vehicle_control_mode.flag_control_allocation_enabled) {
_boat_rudder_act_control.updateActControl();
}
}
void BoatRudder::runSanityChecks()
{
if (_vehicle_control_mode.flag_control_rates_enabled && !_boat_rudder_rate_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
if (_vehicle_control_mode.flag_control_attitude_enabled && !_boat_rudder_att_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
if (_vehicle_control_mode.flag_control_velocity_enabled && !_boat_rudder_speed_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
if (_vehicle_control_mode.flag_control_position_enabled && !_boat_rudder_pos_control.runSanityChecks()) {
_sanity_checks_passed = false;
return;
}
_sanity_checks_passed = true;
}
void BoatRudder::reset()
{
_boat_rudder_pos_control.reset();
_boat_rudder_speed_control.reset();
_boat_rudder_att_control.reset();
_boat_rudder_rate_control.reset();
_boat_rudder_manual_mode.reset();
}
int BoatRudder::task_spawn(int argc, char *argv[])
{
BoatRudder *instance = new BoatRudder();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int BoatRudder::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int BoatRudder::print_usage(const char *reason)
{
if (reason) {
PX4_ERR("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Module for rudder-steered boats.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("boat_rudder", "controller");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int boat_rudder_main(int argc, char *argv[])
{
return BoatRudder::main(argc, argv);
}
+130
View File
@@ -0,0 +1,130 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// Library includes
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_status.h>
// Local includes
#include "BoatRudderActControl/BoatRudderActControl.hpp"
#include "BoatRudderRateControl/BoatRudderRateControl.hpp"
#include "BoatRudderAttControl/BoatRudderAttControl.hpp"
#include "BoatRudderSpeedControl/BoatRudderSpeedControl.hpp"
#include "BoatRudderPosControl/BoatRudderPosControl.hpp"
#include "BoatRudderDriveModes/BoatRudderAutoMode/BoatRudderAutoMode.hpp"
#include "BoatRudderDriveModes/BoatRudderManualMode/BoatRudderManualMode.hpp"
#include "BoatRudderDriveModes/BoatRudderOffboardMode/BoatRudderOffboardMode.hpp"
class BoatRudder : public ModuleBase<BoatRudder>, public ModuleParams,
public px4::ScheduledWorkItem
{
public:
BoatRudder();
~BoatRudder() override = default;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool init();
protected:
void updateParams() override;
private:
void Run() override;
/**
* @brief Generate surface vehicle setpoints if the vehicle is in a
* supported PX4 internal mode.
* Note: The surface vehicle setpoints are expected to be published from outside this module
* if the vehicle is not in a PX4 internal mode.
*/
void generateSetpoints();
void updateControllers();
/**
* @brief Check proper parameter setup for the controllers
*
* Modifies:
*
* - _sanity_checks_passed: true if checks for all active controllers pass
*/
void runSanityChecks();
/**
* @brief Reset controllers and manual mode variables.
*/
void reset();
// uORB subscriptions
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
vehicle_control_mode_s _vehicle_control_mode{};
// Class instances
BoatRudderActControl _boat_rudder_act_control{this};
BoatRudderRateControl _boat_rudder_rate_control{this};
BoatRudderAttControl _boat_rudder_att_control{this};
BoatRudderSpeedControl _boat_rudder_speed_control{this};
BoatRudderPosControl _boat_rudder_pos_control{this};
BoatRudderAutoMode _boat_rudder_auto_mode{this};
BoatRudderManualMode _boat_rudder_manual_mode{this};
BoatRudderOffboardMode _boat_rudder_offboard_mode{this};
// Variables
bool _sanity_checks_passed{true}; // True if checks for all active controllers pass
bool _was_armed{false}; // True if the vehicle was armed before the last reset
};
@@ -0,0 +1,125 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderActControl.hpp"
using namespace time_literals;
BoatRudderActControl::BoatRudderActControl(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
}
void BoatRudderActControl::updateParams()
{
ModuleParams::updateParams();
if (_param_br_str_rate_limit.get() > FLT_EPSILON && _param_br_max_str_ang.get() > FLT_EPSILON) {
_servo_setpoint.setSlewRate((M_DEG_TO_RAD_F * _param_br_str_rate_limit.get()) / _param_br_max_str_ang.get());
}
if (_param_sv_accel_limit.get() > FLT_EPSILON && _param_sv_max_thr_speed.get() > FLT_EPSILON) {
_motor_setpoint.setSlewRate(_param_sv_accel_limit.get() / _param_sv_max_thr_speed.get());
}
}
void BoatRudderActControl::updateActControl()
{
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 10_ms) * 1e-6f;
// Motor control
if (_surface_vehicle_throttle_setpoint_sub.updated()) {
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
_surface_vehicle_throttle_setpoint_sub.copy(&surface_vehicle_throttle_setpoint);
_throttle_setpoint = surface_vehicle_throttle_setpoint.throttle_body_x;
}
if (PX4_ISFINITE(_throttle_setpoint)) {
actuator_motors_s actuator_motors_sub{};
_actuator_motors_sub.copy(&actuator_motors_sub);
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = SurfaceVehicleControl::throttleControl(_motor_setpoint,
_throttle_setpoint, actuator_motors_sub.control[0], _param_sv_accel_limit.get(),
_param_sv_decel_limit.get(), _param_sv_max_thr_speed.get(), dt);
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
}
// Servo control
if (_surface_vehicle_steering_setpoint_sub.updated()) {
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
_surface_vehicle_steering_setpoint_sub.copy(&surface_vehicle_steering_setpoint);
_steering_setpoint = surface_vehicle_steering_setpoint.normalized_steering_setpoint;
}
if (PX4_ISFINITE(_steering_setpoint)) {
actuator_servos_s actuator_servos_sub{};
_actuator_servos_sub.copy(&actuator_servos_sub);
if (_param_br_str_rate_limit.get() > FLT_EPSILON
&& _param_br_max_str_ang.get() > FLT_EPSILON) { // Apply slew rate if configured
if (fabsf(_servo_setpoint.getState() - actuator_servos_sub.control[0]) > fabsf(
_steering_setpoint -
actuator_servos_sub.control[0])) {
_servo_setpoint.setForcedValue(actuator_servos_sub.control[0]);
}
_servo_setpoint.update(_steering_setpoint, dt);
} else {
_servo_setpoint.setForcedValue(_steering_setpoint);
}
actuator_servos_s actuator_servos{};
actuator_servos.control[0] = _servo_setpoint.getState();
actuator_servos.timestamp = _timestamp;
_actuator_servos_pub.publish(actuator_servos);
}
}
void BoatRudderActControl::stopVehicle()
{
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = 0.f;
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
actuator_servos_s actuator_servos{};
actuator_servos.control[0] = 0.f;
actuator_servos.timestamp = _timestamp;
_actuator_servos_pub.publish(actuator_servos);
}
@@ -0,0 +1,111 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_throttle_setpoint.h>
/**
* @brief Class for actuator control of rudder-steered boats.
*/
class BoatRudderActControl : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderActControl.
* @param parent The parent ModuleParams object.
*/
BoatRudderActControl(ModuleParams *parent);
~BoatRudderActControl() = default;
/**
* @brief Generate and publish actuatorMotors/actuatorServos setpoints from SurfaceVehicleThrottleSetpoint/SurfaceVehicleSteeringSetpoint.
*/
void updateActControl();
/**
* @brief Stop the vehicle by sending 0 commands to motors and servos.
*/
void stopVehicle();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
// uORB subscriptions
uORB::Subscription _actuator_servos_sub{ORB_ID(actuator_servos)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _surface_vehicle_steering_setpoint_sub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Subscription _surface_vehicle_throttle_setpoint_sub{ORB_ID(surface_vehicle_throttle_setpoint)};
// uORB publications
uORB::Publication<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
uORB::Publication<actuator_servos_s> _actuator_servos_pub{ORB_ID(actuator_servos)};
// Variables
hrt_abstime _timestamp{0};
float _throttle_setpoint{NAN};
float _steering_setpoint{NAN};
// Controllers
SlewRate<float> _servo_setpoint{0.f};
SlewRate<float> _motor_setpoint{0.f};
// Parameters
DEFINE_PARAMETERS(
(ParamInt<px4::params::CA_R_REV>) _param_r_rev,
(ParamFloat<px4::params::BR_STR_RATE_LIM>) _param_br_str_rate_limit,
(ParamFloat<px4::params::BR_MAX_STR_ANG>) _param_br_max_str_ang,
(ParamFloat<px4::params::SV_ACCEL_LIM>) _param_sv_accel_limit,
(ParamFloat<px4::params::SV_DECEL_LIM>) _param_sv_decel_limit,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed
)
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderActControl
BoatRudderActControl.cpp
)
target_include_directories(BoatRudderActControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,140 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderAttControl.hpp"
using namespace time_literals;
BoatRudderAttControl::BoatRudderAttControl(ModuleParams *parent) : ModuleParams(parent)
{
_surface_vehicle_rate_setpoint_pub.advertise();
_surface_vehicle_attitude_status_pub.advertise();
updateParams();
}
void BoatRudderAttControl::updateParams()
{
ModuleParams::updateParams();
if (_param_sv_yaw_rate_limit.get() > FLT_EPSILON) {
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
// Set up PID controller
_pid_yaw.setGains(_param_sv_yaw_p.get(), 0.f, 0.f);
_pid_yaw.setIntegralLimit(0.f);
_pid_yaw.setOutputLimit(_max_yaw_rate);
// Set up slew rate
_adjusted_yaw_setpoint.setSlewRate(_max_yaw_rate);
}
void BoatRudderAttControl::updateAttControl()
{
updateSubscriptions();
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 10_ms) * 1e-6f;
if (PX4_ISFINITE(_yaw_setpoint)) {
// Calculate yaw rate limit for slew rate
float max_possible_yaw_rate = fabsf(_estimated_speed_body_x) * tanf(_param_br_max_str_ang.get()) /
_param_br_wheel_base.get(); // Maximum possible yaw rate at current velocity
float yaw_slew_rate = math::min(max_possible_yaw_rate, _max_yaw_rate);
float yaw_rate_setpoint = SurfaceVehicleControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, yaw_slew_rate,
_vehicle_yaw, _yaw_setpoint, dt);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = _timestamp;
surface_vehicle_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate);
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
}
// Publish attitude controller status (logging only)
surface_vehicle_attitude_status_s surface_vehicle_attitude_status;
surface_vehicle_attitude_status.timestamp = _timestamp;
surface_vehicle_attitude_status.measured_yaw = _vehicle_yaw;
surface_vehicle_attitude_status.adjusted_yaw_setpoint = matrix::wrap_pi(_adjusted_yaw_setpoint.getState());
_surface_vehicle_attitude_status_pub.publish(surface_vehicle_attitude_status);
}
void BoatRudderAttControl::updateSubscriptions()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
matrix::Quatf vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(vehicle_attitude_quaternion).psi();
}
// Estimate forward speed based on throttle
if (_actuator_motors_sub.updated()) {
actuator_motors_s actuator_motors;
_actuator_motors_sub.copy(&actuator_motors);
_estimated_speed_body_x = math::interpolate<float> (actuator_motors.control[0], -1.f, 1.f,
-_param_sv_max_thr_speed.get(), _param_sv_max_thr_speed.get());
}
if (_surface_vehicle_attitude_setpoint_sub.updated()) {
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
_surface_vehicle_attitude_setpoint_sub.copy(&surface_vehicle_attitude_setpoint);
_yaw_setpoint = surface_vehicle_attitude_setpoint.yaw_setpoint;
}
}
bool BoatRudderAttControl::runSanityChecks()
{
bool ret = true;
if (_param_sv_max_thr_speed.get() < FLT_EPSILON) {
ret = false;
}
if (_param_br_wheel_base.get() < FLT_EPSILON) {
ret = false;
}
if (_param_br_max_str_ang.get() < FLT_EPSILON) {
ret = false;
}
if (_param_sv_yaw_rate_limit.get() < FLT_EPSILON) {
ret = false;
}
return ret;
}
@@ -0,0 +1,126 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Library includes
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/pid/PID.hpp>
#include <lib/slew_rate/SlewRateYaw.hpp>
#include <math.h>
#include <matrix/matrix/math.hpp>
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/surface_vehicle_attitude_status.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/actuator_motors.h>
/**
* @brief Class for attitude control of rudder-steered boats.
*/
class BoatRudderAttControl : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderAttControl.
* @param parent The parent ModuleParams object.
*/
BoatRudderAttControl(ModuleParams *parent);
~BoatRudderAttControl() = default;
/**
* @brief Generate and publish SurfaceVehicleRateSetpoint from SurfaceVehicleAttitudeSetpoint.
*/
void updateAttControl();
/**
* @brief Reset attitude controller.
*/
void reset() {_pid_yaw.resetIntegral(); _yaw_setpoint = NAN;};
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Update uORB subscriptions used in attitude controller.
*/
void updateSubscriptions();
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _surface_vehicle_attitude_setpoint_sub{ORB_ID(surface_vehicle_attitude_setpoint)};
// uORB publications
uORB::Publication<surface_vehicle_rate_setpoint_s> _surface_vehicle_rate_setpoint_pub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Publication<surface_vehicle_attitude_status_s> _surface_vehicle_attitude_status_pub{ORB_ID(surface_vehicle_attitude_status)};
// Variables
float _vehicle_yaw{0.f};
hrt_abstime _timestamp{0};
float _max_yaw_rate{0.f};
float _estimated_speed_body_x{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed_body_x]
between [0, 0] and [1, _param_sv_max_thr_speed].*/
float _yaw_setpoint{NAN};
// Controllers
PID _pid_yaw;
SlewRateYaw<float> _adjusted_yaw_setpoint;
// Parameters
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::BR_WHEEL_BASE>) _param_br_wheel_base,
(ParamFloat<px4::params::BR_MAX_STR_ANG>) _param_br_max_str_ang,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_P>) _param_sv_yaw_p,
(ParamFloat<px4::params::SV_YAW_STICK_DZ>) _param_sv_yaw_stick_dz
)
};
@@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderAttControl
BoatRudderAttControl.cpp
)
target_link_libraries(BoatRudderAttControl PUBLIC PID)
target_include_directories(BoatRudderAttControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,157 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderAutoMode.hpp"
using namespace time_literals;
BoatRudderAutoMode::BoatRudderAutoMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_surface_vehicle_position_setpoint_pub.advertise();
}
void BoatRudderAutoMode::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
if (_param_br_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON
&& _param_br_max_str_ang.get() > FLT_EPSILON) {
_min_speed = _param_br_wheel_base.get() * _max_yaw_rate / tanf(_param_br_max_str_ang.get());
}
}
void BoatRudderAutoMode::autoControl()
{
if (_position_setpoint_triplet_sub.updated()) {
if (_vehicle_local_position_sub.updated()) {
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
if (!_global_ned_proj_ref.isInitialized()
|| (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) {
_global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon,
vehicle_local_position.ref_timestamp);
}
_curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y);
}
updateWaypointsAndAcceptanceRadius();
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = _curr_wp_ned(0);
surface_vehicle_position_setpoint.position_ned[1] = _curr_wp_ned(1);
surface_vehicle_position_setpoint.start_ned[0] = _prev_wp_ned(0);
surface_vehicle_position_setpoint.start_ned[1] = _prev_wp_ned(1);
surface_vehicle_position_setpoint.arrival_speed = arrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius,
_curr_wp_type,
_waypoint_transition_angle, _max_yaw_rate);
surface_vehicle_position_setpoint.cruising_speed = _cruising_speed;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
}
}
void BoatRudderAutoMode::updateWaypointsAndAcceptanceRadius()
{
position_setpoint_triplet_s position_setpoint_triplet{};
_position_setpoint_triplet_sub.copy(&position_setpoint_triplet);
_curr_wp_type = position_setpoint_triplet.current.type;
SurfaceVehicleControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet,
_curr_pos_ned, _global_ned_proj_ref);
_waypoint_transition_angle = SurfaceVehicleControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned,
_next_wp_ned);
// Update acceptance radius
if (_param_br_acc_rad_max.get() >= _param_nav_acc_rad.get()) {
_acceptance_radius = updateAcceptanceRadius(_waypoint_transition_angle, _param_nav_acc_rad.get(),
_param_br_acc_rad_gain.get(), _param_br_acc_rad_max.get(), _param_br_wheel_base.get(), _param_br_max_str_ang.get());
} else {
_acceptance_radius = _param_nav_acc_rad.get();
}
// Waypoint cruising speed
_cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain(
position_setpoint_triplet.current.cruising_speed, 0.f, _param_sv_speed_limit.get()) : _param_sv_speed_limit.get();
}
float BoatRudderAutoMode::updateAcceptanceRadius(const float waypoint_transition_angle,
const float default_acceptance_radius, const float acceptance_radius_gain,
const float acceptance_radius_max, const float wheel_base, const float max_steer_angle)
{
// Calculate acceptance radius s.t. the rover cuts the corner tangential to the current and next line segment
float acceptance_radius = default_acceptance_radius;
if (PX4_ISFINITE(_waypoint_transition_angle)) {
const float theta = waypoint_transition_angle / 2.f;
const float min_turning_radius = wheel_base / sinf(max_steer_angle);
const float acceptance_radius_temp = min_turning_radius / tanf(theta);
const float acceptance_radius_temp_scaled = acceptance_radius_gain *
acceptance_radius_temp; // Scale geometric ideal acceptance radius to account for kinematic and dynamic effects
acceptance_radius = math::constrain<float>(acceptance_radius_temp_scaled, default_acceptance_radius,
acceptance_radius_max);
}
// Publish updated acceptance radius
position_controller_status_s pos_ctrl_status{};
pos_ctrl_status.acceptance_radius = acceptance_radius;
pos_ctrl_status.timestamp = hrt_absolute_time();
_position_controller_status_pub.publish(pos_ctrl_status);
return acceptance_radius;
}
float BoatRudderAutoMode::arrivalSpeed(const float cruising_speed, const float min_speed, const float acc_rad,
const int curr_wp_type, const float waypoint_transition_angle, const float max_yaw_rate)
{
if (!PX4_ISFINITE(waypoint_transition_angle)
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_LAND
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) {
return 0.f; // Stop at the waypoint
} else if (_param_sv_speed_red.get() > FLT_EPSILON) {
const float speed_reduction = math::constrain(_param_sv_speed_red.get() * math::interpolate(
M_PI_F - waypoint_transition_angle,
0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f);
return math::constrain(_param_sv_max_thr_speed.get() * (1.f - speed_reduction), min_speed,
cruising_speed); // Slow down for cornering
}
return cruising_speed; // Fallthrough
}
@@ -0,0 +1,140 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/position_controller_status.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
/**
* @brief Class for auto mode for rudder-steered boats.
*/
class BoatRudderAutoMode : public ModuleParams
{
public:
/**
* @brief Constructor for auto mode.
* @param parent The parent ModuleParams object.
*/
BoatRudderAutoMode(ModuleParams *parent);
~BoatRudderAutoMode() = default;
/**
* @brief Generate and publish SurfaceVehiclePositionSetpoint from positionSetpointTriplet.
*/
void autoControl();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Update global/NED waypoint coordinates and acceptance radius.
*/
void updateWaypointsAndAcceptanceRadius();
/**
* @brief Publish the acceptance radius for current waypoint based on the angle between a line segment
* from the previous to the current waypoint/current to the next waypoint and maximum steer angle of the vehicle.
* @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
* @param default_acceptance_radius Default acceptance radius for waypoints [m].
* @param acceptance_radius_gain Tuning parameter that scales the geometric optimal acceptance radius for the corner cutting [-].
* @param acceptance_radius_max Maximum value for the acceptance radius [m].
* @param wheel_base Rover wheelbase [m].
* @param max_steer_angle Rover maximum steer angle [rad].
* @return Updated acceptance radius [m].
*/
float updateAcceptanceRadius(float waypoint_transition_angle, float default_acceptance_radius,
float acceptance_radius_gain, float acceptance_radius_max, float wheel_base, float max_steer_angle);
/**
* @brief Calculate the speed at which the rover should arrive at the current waypoint based on the upcoming corner.
* @param cruising_speed Cruising speed [m/s].
* @param min_speed Minimum speed setpoint [m/s].
* @param acc_rad Acceptance radius of the current waypoint [m].
* @param curr_wp_type Type of the current waypoint.
* @param waypoint_transition_angle Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
* @param max_yaw_rate Maximum yaw rate setpoint [rad/s]
* @return Speed setpoint [m/s].
*/
float arrivalSpeed(float cruising_speed, float min_speed, float acc_rad, int curr_wp_type,
float waypoint_transition_angle, float max_yaw_rate);
// uORB subscriptions
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)};
// uORB publications
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Publication<position_controller_status_s> _position_controller_status_pub{ORB_ID(position_controller_status)};
// Variables
MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates
Vector2f _curr_wp_ned{NAN, NAN};
Vector2f _prev_wp_ned{NAN, NAN};
Vector2f _next_wp_ned{NAN, NAN};
Vector2f _curr_pos_ned{NAN, NAN};
float _acceptance_radius{0.5f};
float _cruising_speed{0.f};
float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad]
float _max_yaw_rate{NAN};
float _min_speed{NAN}; // Speed at which the maximum yaw rate limit is enforced given the maximum steer angle and wheel base.
int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit,
(ParamFloat<px4::params::BR_WHEEL_BASE>) _param_br_wheel_base,
(ParamFloat<px4::params::BR_MAX_STR_ANG>) _param_br_max_str_ang,
(ParamFloat<px4::params::NAV_ACC_RAD>) _param_nav_acc_rad,
(ParamFloat<px4::params::BR_ACC_RAD_MAX>) _param_br_acc_rad_max,
(ParamFloat<px4::params::BR_ACC_RAD_GAIN>) _param_br_acc_rad_gain,
(ParamFloat<px4::params::SV_SPEED_RED>) _param_sv_speed_red,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed
)
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderAutoMode
BoatRudderAutoMode.cpp
)
target_include_directories(BoatRudderAutoMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,227 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderManualMode.hpp"
using namespace time_literals;
BoatRudderManualMode::BoatRudderManualMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_surface_vehicle_throttle_setpoint_pub.advertise();
_surface_vehicle_steering_setpoint_pub.advertise();
_surface_vehicle_rate_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_position_setpoint_pub.advertise();
}
void BoatRudderManualMode::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
void BoatRudderManualMode::manual()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_steering_setpoint.normalized_steering_setpoint = manual_control_setpoint.roll;
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
}
void BoatRudderManualMode::acro()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>
(manual_control_setpoint.roll, _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
}
void BoatRudderManualMode::stab()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi();
}
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON
|| fabsf(surface_vehicle_throttle_setpoint.throttle_body_x) < FLT_EPSILON) {
_stab_yaw_setpoint = NAN;
// Rate control
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_sv_yaw_stick_dz.get()), _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
// Set uncontrolled setpoint invalid
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = NAN;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
} else { // Heading control
if (!PX4_ISFINITE(_stab_yaw_setpoint)) {
_stab_yaw_setpoint = _vehicle_yaw;
}
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
}
}
void BoatRudderManualMode::position()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi();
}
if (_vehicle_local_position_sub.updated()) {
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
if (!_global_ned_proj_ref.isInitialized()
|| (_global_ned_proj_ref.getProjectionReferenceTimestamp() != vehicle_local_position.ref_timestamp)) {
_global_ned_proj_ref.initReference(vehicle_local_position.ref_lat, vehicle_local_position.ref_lon,
vehicle_local_position.ref_timestamp);
}
_curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y);
}
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
const float speed_setpoint = math::interpolate<float>(manual_control_setpoint.throttle,
-1.f, 1.f, -_param_sv_speed_limit.get(), _param_sv_speed_limit.get());
if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON
|| fabsf(speed_setpoint) < FLT_EPSILON) {
_pos_ctl_course_direction = Vector2f(NAN, NAN);
// Speed control
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_speed_setpoint.speed_body_x = speed_setpoint;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
// Rate control
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_sv_yaw_stick_dz.get()), _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
// Set uncontrolled setpoints invalid
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = NAN;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = NAN;
surface_vehicle_position_setpoint.position_ned[1] = NAN;
surface_vehicle_position_setpoint.start_ned[0] = NAN;
surface_vehicle_position_setpoint.start_ned[1] = NAN;
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.cruising_speed = NAN;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
} else { // Course control
if (!_pos_ctl_course_direction.isAllFinite()) {
_pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw));
_pos_ctl_start_position_ned = _curr_pos_ned;
}
// Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover
const Vector2f start_to_curr_pos = _curr_pos_ned - _pos_ctl_start_position_ned;
const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get();
const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) *
vector_scaling * _pos_ctl_course_direction;
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = target_waypoint_ned(0);
surface_vehicle_position_setpoint.position_ned[1] = target_waypoint_ned(1);
surface_vehicle_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0);
surface_vehicle_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1);
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.cruising_speed = speed_setpoint;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
}
}
void BoatRudderManualMode::reset()
{
_stab_yaw_setpoint = NAN;
_pos_ctl_course_direction = Vector2f(NAN, NAN);
_pos_ctl_start_position_ned = Vector2f(NAN, NAN);
_curr_pos_ned = Vector2f(NAN, NAN);
}
@@ -0,0 +1,134 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <math.h>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/surface_vehicle_throttle_setpoint.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
/**
* @brief Class for manual modes for rudder-steered boats.
*/
class BoatRudderManualMode : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderManualMode.
* @param parent The parent ModuleParams object.
*/
BoatRudderManualMode(ModuleParams *parent);
~BoatRudderManualMode() = default;
/**
* @brief Publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleSteeringSetpoint from manualControlSetpoint.
*/
void manual();
/**
* @brief Generate and publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleRateSetpoint from manualControlSetpoint.
*/
void acro();
/**
* @brief Generate and publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleAttitudeSetpoint from manualControlSetpoint.
*/
void stab();
/**
* @brief Generate and publish SurfaceVehicleSpeedSetpoint/SurfaceVehicleRateSetpoint or SurfaceVehiclePositionSetpoint from manualControlSetpoint.
*/
void position();
/**
* @brief Reset manual mode variables.
*/
void reset();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
// uORB publications
uORB::Publication<surface_vehicle_throttle_setpoint_s> _surface_vehicle_throttle_setpoint_pub{ORB_ID(surface_vehicle_throttle_setpoint)};
uORB::Publication<surface_vehicle_steering_setpoint_s> _surface_vehicle_steering_setpoint_pub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Publication<surface_vehicle_rate_setpoint_s> _surface_vehicle_rate_setpoint_pub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
// Variables
MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates
Quatf _vehicle_attitude_quaternion{};
Vector2f _pos_ctl_course_direction{NAN, NAN};
Vector2f _pos_ctl_start_position_ned{NAN, NAN};
Vector2f _curr_pos_ned{NAN, NAN};
float _stab_yaw_setpoint{NAN};
float _vehicle_yaw{NAN};
float _max_yaw_rate{NAN};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_P>) _param_sv_yaw_p,
(ParamFloat<px4::params::SV_YAW_STICK_DZ>) _param_sv_yaw_stick_dz,
(ParamFloat<px4::params::SV_YAW_EXPO>) _param_sv_yaw_expo,
(ParamFloat<px4::params::SV_YAW_SUPEXPO>) _param_sv_yaw_supexpo,
(ParamFloat<px4::params::PP_LOOKAHD_MAX>) _param_pp_lookahd_max,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit
)
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderManualMode
BoatRudderManualMode.cpp
)
target_include_directories(BoatRudderManualMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,82 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderOffboardMode.hpp"
using namespace time_literals;
BoatRudderOffboardMode::BoatRudderOffboardMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_position_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
}
void BoatRudderOffboardMode::updateParams()
{
ModuleParams::updateParams();
}
void BoatRudderOffboardMode::offboardControl()
{
offboard_control_mode_s offboard_control_mode{};
_offboard_control_mode_sub.copy(&offboard_control_mode);
trajectory_setpoint_s trajectory_setpoint{};
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (offboard_control_mode.position) {
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = trajectory_setpoint.position[0];
surface_vehicle_position_setpoint.position_ned[1] = trajectory_setpoint.position[1];
surface_vehicle_position_setpoint.start_ned[0] = NAN;
surface_vehicle_position_setpoint.start_ned[1] = NAN;
surface_vehicle_position_setpoint.cruising_speed = NAN;
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
} else if (offboard_control_mode.velocity) {
const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_speed_setpoint.speed_body_x = velocity_ned.norm();
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = atan2f(velocity_ned(1), velocity_ned(0));
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
}
}
@@ -0,0 +1,87 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
// Libraries
#include <math.h>
#include <matrix/matrix/math.hpp>
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
using namespace matrix;
/**
* @brief Class for offboard mode for rudder-steered boats.
*/
class BoatRudderOffboardMode : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderOffboardMode.
* @param parent The parent ModuleParams object.
*/
BoatRudderOffboardMode(ModuleParams *parent);
~BoatRudderOffboardMode() = default;
/**
* @brief Generate and publish roverSetpoints from trajectorySetpoint.
*/
void offboardControl();
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
// uORB subscriptions
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
// uORB publications
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
};
@@ -0,0 +1,38 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderOffboardMode
BoatRudderOffboardMode.cpp
)
target_include_directories(BoatRudderOffboardMode PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(BoatRudderAutoMode)
add_subdirectory(BoatRudderManualMode)
add_subdirectory(BoatRudderOffboardMode)
@@ -0,0 +1,176 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderPosControl.hpp"
using namespace time_literals;
BoatRudderPosControl::BoatRudderPosControl(ModuleParams *parent) : ModuleParams(parent)
{
_pure_pursuit_status_pub.advertise();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
updateParams();
}
void BoatRudderPosControl::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_min_speed = _param_br_wheel_base.get() * _max_yaw_rate / tanf(_param_br_max_str_ang.get());
}
void BoatRudderPosControl::updatePosControl()
{
updateSubscriptions();
hrt_abstime timestamp = hrt_absolute_time();
if (_target_waypoint_ned.isAllFinite()) {
float distance_to_target = (_target_waypoint_ned - _curr_pos_ned).norm();
if (_arrival_speed > FLT_EPSILON) {
distance_to_target -= _acceptance_radius; // shift target to the edge of the acceptance radius if arrival speed not zero
}
if (distance_to_target > _acceptance_radius || _arrival_speed > FLT_EPSILON) {
float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_sv_jerk_limit.get(),
_param_sv_decel_limit.get(), distance_to_target, fabsf(_arrival_speed));
speed_setpoint = math::min(speed_setpoint, _cruising_speed);
pure_pursuit_status_s pure_pursuit_status{};
pure_pursuit_status.timestamp = timestamp;
const float bearing_setpoint = PurePursuit::calcTargetBearing(pure_pursuit_status, _param_pp_lookahd_gain.get(),
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), _target_waypoint_ned, _start_ned,
_curr_pos_ned, fabsf(speed_setpoint));
if (_param_sv_speed_red.get() > FLT_EPSILON) {
const float course_error = fabsf(matrix::wrap_pi(bearing_setpoint - _vehicle_yaw));
const float speed_reduction = math::constrain(_param_sv_speed_red.get() * math::interpolate(course_error,
0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f);
const float max_speed = math::constrain(_param_sv_max_thr_speed.get() * (1.f - speed_reduction), _min_speed,
_param_sv_max_thr_speed.get());
speed_setpoint = math::constrain(speed_setpoint, -max_speed, max_speed);
}
_pure_pursuit_status_pub.publish(pure_pursuit_status);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = timestamp;
surface_vehicle_speed_setpoint.speed_body_x = speed_setpoint;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = timestamp;
surface_vehicle_attitude_setpoint.yaw_setpoint = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi(
bearing_setpoint + M_PI_F);
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
} else {
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = timestamp;
surface_vehicle_speed_setpoint.speed_body_x = 0.f;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = timestamp;
surface_vehicle_attitude_setpoint.yaw_setpoint = _vehicle_yaw;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
if (!_stopped && fabsf(_vehicle_speed) < FLT_EPSILON) {
_stopped = true;
_target_waypoint_ned = _curr_pos_ned;
}
if (_stopped && _updated_reset_counter != _reset_counter) {
_target_waypoint_ned = _curr_pos_ned;
_reset_counter = _updated_reset_counter;
}
}
}
}
void BoatRudderPosControl::updateSubscriptions()
{
if (_position_controller_status_sub.updated()) {
position_controller_status_s position_controller_status{};
_position_controller_status_sub.copy(&position_controller_status);
_acceptance_radius = position_controller_status.acceptance_radius;
}
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
_vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi();
}
if (_vehicle_local_position_sub.updated()) {
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
_updated_reset_counter = vehicle_local_position.xy_reset_counter;
_curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y);
Vector3f velocity_ned(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz);
Vector3f velocity_xyz = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_ned);
Vector2f velocity_2d = Vector2f(velocity_xyz(0), velocity_xyz(1));
_vehicle_speed = velocity_2d.norm() > _param_sv_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f;
}
if (_surface_vehicle_position_setpoint_sub.updated()) {
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint;
_surface_vehicle_position_setpoint_sub.copy(&surface_vehicle_position_setpoint);
_start_ned = Vector2f(surface_vehicle_position_setpoint.start_ned[0], surface_vehicle_position_setpoint.start_ned[1]);
_start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned;
_arrival_speed = PX4_ISFINITE(surface_vehicle_position_setpoint.arrival_speed) ?
surface_vehicle_position_setpoint.arrival_speed : 0.f;
_cruising_speed = PX4_ISFINITE(surface_vehicle_position_setpoint.cruising_speed) ?
surface_vehicle_position_setpoint.cruising_speed :
_param_sv_speed_limit.get();
_target_waypoint_ned = Vector2f(surface_vehicle_position_setpoint.position_ned[0],
surface_vehicle_position_setpoint.position_ned[1]);
_stopped = false;
}
}
bool BoatRudderPosControl::runSanityChecks()
{
bool ret = true;
if (_param_sv_speed_limit.get() < FLT_EPSILON) {
ret = false;
}
return ret;
}
@@ -0,0 +1,140 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/events.h>
// Library includes
#include <matrix/matrix/math.hpp>
#include <lib/pure_pursuit/PurePursuit.hpp>
#include <math.h>
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/position_controller_status.h>
#include <uORB/topics/pure_pursuit_status.h>
using namespace matrix;
/**
* @brief Class for position control of rudder-steered boats.
*/
class BoatRudderPosControl : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderPosControl.
* @param parent The parent ModuleParams object.
*/
BoatRudderPosControl(ModuleParams *parent);
~BoatRudderPosControl() = default;
/**
* @brief Generate and publish SurfaceVehicleSpeedSetpoint and SurfaceVehicleAttitudeSetpoint from SurfaceVehiclePositionSetpoint.
*/
void updatePosControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
/**
* @brief Reset position controller.
*/
void reset() {_start_ned = Vector2f{NAN, NAN}; _target_waypoint_ned = Vector2f{NAN, NAN}; _arrival_speed = 0.f; _cruising_speed = _param_sv_speed_limit.get(); _stopped = false;};
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Update uORB subscriptions used in position controller.
*/
void updateSubscriptions();
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _surface_vehicle_position_setpoint_sub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Subscription _position_controller_status_sub{ORB_ID(position_controller_status)};
// uORB publications
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
uORB::Publication<pure_pursuit_status_s> _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)};
// Variables
Quatf _vehicle_attitude_quaternion{};
Vector2f _curr_pos_ned{};
Vector2f _start_ned{};
Vector2f _target_waypoint_ned{};
float _arrival_speed{0.f};
float _vehicle_yaw{0.f};
float _max_yaw_rate{0.f};
float _acceptance_radius{0.f}; // Acceptance radius for the waypoint.
float _min_speed{NAN};
float _vehicle_speed{0.f};
float _cruising_speed{NAN};
bool _stopped{false};
uint8_t _reset_counter{0}; /**< counter for estimator resets in xy-direction */
uint8_t _updated_reset_counter{0}; /**< counter for estimator resets in xy-direction */
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::SV_SPEED_RED>) _param_sv_speed_red,
(ParamFloat<px4::params::SV_DECEL_LIM>) _param_sv_decel_limit,
(ParamFloat<px4::params::SV_JERK_LIM>) _param_sv_jerk_limit,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit,
(ParamFloat<px4::params::PP_LOOKAHD_GAIN>) _param_pp_lookahd_gain,
(ParamFloat<px4::params::PP_LOOKAHD_MAX>) _param_pp_lookahd_max,
(ParamFloat<px4::params::PP_LOOKAHD_MIN>) _param_pp_lookahd_min,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::BR_WHEEL_BASE>) _param_br_wheel_base,
(ParamFloat<px4::params::BR_MAX_STR_ANG>) _param_br_max_str_ang,
(ParamFloat<px4::params::SV_SPEED_TH>) _param_sv_speed_th
)
};
@@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderPosControl
BoatRudderPosControl.cpp
)
target_link_libraries(BoatRudderPosControl PUBLIC PID)
target_include_directories(BoatRudderPosControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,182 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderRateControl.hpp"
using namespace time_literals;
BoatRudderRateControl::BoatRudderRateControl(ModuleParams *parent) : ModuleParams(parent)
{
_surface_vehicle_steering_setpoint_pub.advertise();
_surface_vehicle_rate_status_pub.advertise();
updateParams();
}
void BoatRudderRateControl::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
// Set up PID controller
_pid_yaw_rate.setGains(_param_sv_yaw_rate_p.get(), _param_sv_yaw_rate_i.get(), 0.f);
_pid_yaw_rate.setIntegralLimit(1.f);
_pid_yaw_rate.setOutputLimit(1.f);
// Set up slew rate
_adjusted_yaw_rate_setpoint.setSlewRate(_param_sv_yaw_accel_limit.get() * M_DEG_TO_RAD_F);
}
void BoatRudderRateControl::updateRateControl()
{
updateSubscriptions();
hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 10_ms) * 1e-6f;
if (PX4_ISFINITE(_yaw_rate_setpoint)) {
if (fabsf(_estimated_speed) > FLT_EPSILON) {
// Set up feasible yaw rate setpoint
float steering_setpoint{0.f};
float max_possible_yaw_rate = fabsf(_estimated_speed) * tanf(_param_br_max_str_ang.get()) /
_param_br_wheel_base.get(); // Maximum possible yaw rate at current velocity
float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate);
float constrained_yaw_rate = math::constrain(_yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit);
if (_param_sv_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured
if (fabsf(_adjusted_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate -
_vehicle_yaw_rate)) {
_adjusted_yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate);
}
_adjusted_yaw_rate_setpoint.update(constrained_yaw_rate, dt);
} else {
_adjusted_yaw_rate_setpoint.setForcedValue(constrained_yaw_rate);
}
// Feed forward
steering_setpoint = atanf(_adjusted_yaw_rate_setpoint.getState() * _param_br_wheel_base.get() / _estimated_speed) *
_param_sv_yaw_rate_corr.get();
// Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability)
if (_estimated_speed > FLT_EPSILON) {
_pid_yaw_rate.setSetpoint(_adjusted_yaw_rate_setpoint.getState());
steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, dt);
}
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = _timestamp;
surface_vehicle_steering_setpoint.normalized_steering_setpoint = math::interpolate<float>(steering_setpoint,
-_param_br_max_str_ang.get(), _param_br_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
} else {
_pid_yaw_rate.resetIntegral();
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = _timestamp;
surface_vehicle_steering_setpoint.normalized_steering_setpoint = 0.f;
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
}
}
// Publish rate controller status (logging only)
surface_vehicle_rate_status_s surface_vehicle_rate_status;
surface_vehicle_rate_status.timestamp = _timestamp;
surface_vehicle_rate_status.measured_yaw_rate = _vehicle_yaw_rate;
surface_vehicle_rate_status.adjusted_yaw_rate_setpoint = _adjusted_yaw_rate_setpoint.getState();
surface_vehicle_rate_status.pid_yaw_rate_integral = _pid_yaw_rate.getIntegral();
_surface_vehicle_rate_status_pub.publish(surface_vehicle_rate_status);
}
void BoatRudderRateControl::updateSubscriptions()
{
if (_vehicle_angular_velocity_sub.updated()) {
vehicle_angular_velocity_s vehicle_angular_velocity{};
_vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity);
_vehicle_yaw_rate = fabsf(vehicle_angular_velocity.xyz[2]) > _param_sv_yaw_rate_th.get() * M_DEG_TO_RAD_F ?
vehicle_angular_velocity.xyz[2] : 0.f;
}
// Estimate forward speed based on throttle
if (_actuator_motors_sub.updated()) {
actuator_motors_s actuator_motors;
_actuator_motors_sub.copy(&actuator_motors);
_estimated_speed = math::interpolate<float>(actuator_motors.control[0], -1.f, 1.f,
-_param_sv_max_thr_speed.get(), _param_sv_max_thr_speed.get());
_estimated_speed = fabsf(_estimated_speed) > _param_sv_speed_th.get() ? _estimated_speed : 0.f;
}
if (_surface_vehicle_rate_setpoint_sub.updated()) {
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
_surface_vehicle_rate_setpoint_sub.copy(&surface_vehicle_rate_setpoint);
_yaw_rate_setpoint = surface_vehicle_rate_setpoint.yaw_rate_setpoint;
}
}
bool BoatRudderRateControl::runSanityChecks()
{
bool ret = true;
if (_param_sv_max_thr_speed.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("boat_rudder_rate_control_conf_invalid_max_thr_speed"), events::Log::Error,
"Invalid configuration of necessary parameter SV_MAX_THR_SPEED", _param_sv_max_thr_speed.get());
}
if (_param_br_wheel_base.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("boat_rudder_rate_control_conf_invalid_wheel_base"), events::Log::Error,
"Invalid configuration of necessary parameter RA_WHEEL_BASE", _param_br_wheel_base.get());
}
if (_param_br_max_str_ang.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("boat_rudder_rate_control_conf_invalid_max_str_ang"), events::Log::Error,
"Invalid configuration of necessary parameter RA_MAX_STR_ANG", _param_br_max_str_ang.get());
}
if (_param_sv_yaw_rate_limit.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("boat_rudder_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error,
"Invalid configuration of necessary parameter SV_YAW_RATE_LIM", _param_sv_yaw_rate_limit.get());
}
return ret;
}
@@ -0,0 +1,129 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/events.h>
// Libraries
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/pid/PID.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/vehicle_angular_velocity.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_status.h>
#include <uORB/topics/actuator_motors.h>
/**
* @brief Class for rate control of rudder-steered boats.
*/
class BoatRudderRateControl : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderRateControl.
* @param parent The parent ModuleParams object.
*/
BoatRudderRateControl(ModuleParams *parent);
~BoatRudderRateControl() = default;
/**
* @brief Generate and publish SurfaceVehicleSteeringSetpoint from SurfaceVehicleRateSetpoint.
*/
void updateRateControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
/**
* @brief Reset rate controller.
*/
void reset() {_pid_yaw_rate.resetIntegral(); _yaw_rate_setpoint = NAN;};
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Update uORB subscriptions used in rate controller.
*/
void updateSubscriptions();
// uORB subscriptions
uORB::Subscription _surface_vehicle_rate_setpoint_sub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
// uORB publications
uORB::Publication<surface_vehicle_steering_setpoint_s> _surface_vehicle_steering_setpoint_pub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Publication<surface_vehicle_rate_status_s> _surface_vehicle_rate_status_pub{ORB_ID(surface_vehicle_rate_status)};
// Variables
float _estimated_speed{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed]
between [0, 0] and [1, _param_sv_max_thr_speed].*/
float _max_yaw_rate{0.f};
float _vehicle_yaw_rate{0.f};
float _yaw_rate_setpoint{NAN};
hrt_abstime _timestamp{0};
// Controllers
PID _pid_yaw_rate;
SlewRate<float> _adjusted_yaw_rate_setpoint{0.f};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::BR_WHEEL_BASE>) _param_br_wheel_base,
(ParamFloat<px4::params::BR_MAX_STR_ANG>) _param_br_max_str_ang,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_RATE_TH>) _param_sv_yaw_rate_th,
(ParamFloat<px4::params::SV_YAW_RATE_P>) _param_sv_yaw_rate_p,
(ParamFloat<px4::params::SV_YAW_RATE_I>) _param_sv_yaw_rate_i,
(ParamFloat<px4::params::SV_YAW_ACCEL_LIM>) _param_sv_yaw_accel_limit,
(ParamFloat<px4::params::SV_SPEED_TH>) _param_sv_speed_th,
(ParamFloat<px4::params::SV_YAW_RATE_CORR>) _param_sv_yaw_rate_corr
)
};
@@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderRateControl
BoatRudderRateControl.cpp
)
target_link_libraries(BoatRudderRateControl PUBLIC PID)
target_include_directories(BoatRudderRateControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -0,0 +1,134 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "BoatRudderSpeedControl.hpp"
using namespace time_literals;
BoatRudderSpeedControl::BoatRudderSpeedControl(ModuleParams *parent) : ModuleParams(parent)
{
_surface_vehicle_throttle_setpoint_pub.advertise();
_surface_vehicle_speed_status_pub.advertise();
updateParams();
}
void BoatRudderSpeedControl::updateParams()
{
ModuleParams::updateParams();
// Set up PID controller
_pid_speed.setGains(_param_sv_speed_p.get(), _param_sv_speed_i.get(), 0.f);
_pid_speed.setIntegralLimit(1.f);
_pid_speed.setOutputLimit(1.f);
// Set up slew rate
if (_param_sv_accel_limit.get() > FLT_EPSILON) {
_adjusted_speed_setpoint.setSlewRate(_param_sv_accel_limit.get());
}
}
void BoatRudderSpeedControl::updateSpeedControl()
{
updateSubscriptions();
const hrt_abstime timestamp_prev = _timestamp;
_timestamp = hrt_absolute_time();
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 10_ms) * 1e-6f;
// Throttle Setpoint
if (PX4_ISFINITE(_speed_setpoint)) {
const float speed_setpoint = math::constrain(_speed_setpoint, -_param_sv_speed_limit.get(),
_param_sv_speed_limit.get());
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = _timestamp;
surface_vehicle_throttle_setpoint.throttle_body_x = SurfaceVehicleControl::speedControl(_adjusted_speed_setpoint,
_pid_speed,
speed_setpoint, _vehicle_speed, _param_sv_accel_limit.get(), _param_sv_decel_limit.get(),
_param_sv_max_thr_speed.get(), dt);
surface_vehicle_throttle_setpoint.throttle_body_y = NAN;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
}
// Publish speed controller status (logging only)
surface_vehicle_speed_status_s surface_vehicle_speed_status;
surface_vehicle_speed_status.timestamp = _timestamp;
surface_vehicle_speed_status.measured_speed_body_x = _vehicle_speed;
surface_vehicle_speed_status.adjusted_speed_body_x_setpoint = _adjusted_speed_setpoint.getState();
surface_vehicle_speed_status.pid_throttle_body_x_integral = _pid_speed.getIntegral();
surface_vehicle_speed_status.measured_speed_body_y = NAN;
surface_vehicle_speed_status.adjusted_speed_body_y_setpoint = NAN;
surface_vehicle_speed_status.pid_throttle_body_y_integral = NAN;
_surface_vehicle_speed_status_pub.publish(surface_vehicle_speed_status);
}
void BoatRudderSpeedControl::updateSubscriptions()
{
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude{};
_vehicle_attitude_sub.copy(&vehicle_attitude);
_vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q);
}
if (_vehicle_local_position_sub.updated()) {
vehicle_local_position_s vehicle_local_position{};
_vehicle_local_position_sub.copy(&vehicle_local_position);
Vector3f velocity_ned(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz);
Vector3f velocity_xyz = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_ned);
Vector2f velocity_2d = Vector2f(velocity_xyz(0), velocity_xyz(1));
_vehicle_speed = velocity_2d.norm() > _param_sv_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f;
}
if (_surface_vehicle_speed_setpoint_sub.updated()) {
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint;
_surface_vehicle_speed_setpoint_sub.copy(&surface_vehicle_speed_setpoint);
_speed_setpoint = surface_vehicle_speed_setpoint.speed_body_x;
}
}
bool BoatRudderSpeedControl::runSanityChecks()
{
bool ret = true;
if (_param_sv_max_thr_speed.get() < FLT_EPSILON) {
ret = false;
}
if (_param_sv_speed_limit.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("boat_rudder_speed_control_conf_invalid_speed_lim"), events::Log::Error,
"Invalid configuration of necessary parameter SV_SPEED_LIM", _param_sv_speed_limit.get());
}
return ret;
}
@@ -0,0 +1,128 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/events.h>
// Library includes
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/pid/PID.hpp>
#include <matrix/matrix/math.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/surface_vehicle_throttle_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_status.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
using namespace matrix;
/**
* @brief Class for speed control of rudder-steered boats.
*/
class BoatRudderSpeedControl : public ModuleParams
{
public:
/**
* @brief Constructor for BoatRudderSpeedControl.
* @param parent The parent ModuleParams object.
*/
BoatRudderSpeedControl(ModuleParams *parent);
~BoatRudderSpeedControl() = default;
/**
* @brief Generate and publish SurfaceVehicleThrottleSetpoint from SurfaceVehicleSpeedSetpoint.
*/
void updateSpeedControl();
/**
* @brief Check if the necessary parameters are set.
* @return True if all checks pass.
*/
bool runSanityChecks();
/**
* @brief Reset speed controller.
*/
void reset() {_pid_speed.resetIntegral(); _speed_setpoint = NAN; _adjusted_speed_setpoint.setForcedValue(0.f);};
protected:
/**
* @brief Update the parameters of the module.
*/
void updateParams() override;
private:
/**
* @brief Update uORB subscriptions used in speed controller.
*/
void updateSubscriptions();
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _surface_vehicle_speed_setpoint_sub{ORB_ID(surface_vehicle_speed_setpoint)};
// uORB publications
uORB::Publication<surface_vehicle_throttle_setpoint_s> _surface_vehicle_throttle_setpoint_pub{ORB_ID(surface_vehicle_throttle_setpoint)};
uORB::Publication<surface_vehicle_speed_status_s> _surface_vehicle_speed_status_pub{ORB_ID(surface_vehicle_speed_status)};
// Variables
hrt_abstime _timestamp{0};
Quatf _vehicle_attitude_quaternion{};
float _vehicle_speed{0.f}; // [m/s] Positiv: Forwards, Negativ: Backwards
float _speed_setpoint{NAN};
// Controllers
PID _pid_speed;
SlewRate<float> _adjusted_speed_setpoint{0.f};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::SV_SPEED_P>) _param_sv_speed_p,
(ParamFloat<px4::params::SV_SPEED_I>) _param_sv_speed_i,
(ParamFloat<px4::params::SV_ACCEL_LIM>) _param_sv_accel_limit,
(ParamFloat<px4::params::SV_DECEL_LIM>) _param_sv_decel_limit,
(ParamFloat<px4::params::SV_JERK_LIM>) _param_sv_jerk_limit,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit,
(ParamFloat<px4::params::SV_SPEED_TH>) _param_sv_speed_th
)
};
@@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(BoatRudderSpeedControl
BoatRudderSpeedControl.cpp
)
target_link_libraries(BoatRudderSpeedControl PUBLIC PID)
target_include_directories(BoatRudderSpeedControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
+61
View File
@@ -0,0 +1,61 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(BoatRudderActControl)
add_subdirectory(BoatRudderRateControl)
add_subdirectory(BoatRudderAttControl)
add_subdirectory(BoatRudderSpeedControl)
add_subdirectory(BoatRudderPosControl)
add_subdirectory(BoatRudderDriveModes)
px4_add_module(
MODULE modules__boat_rudder
MAIN boat_rudder
SRCS
BoatRudder.cpp
BoatRudder.hpp
DEPENDS
BoatRudderActControl
BoatRudderRateControl
BoatRudderAttControl
BoatRudderSpeedControl
BoatRudderPosControl
BoatRudderAutoMode
BoatRudderManualMode
BoatRudderOffboardMode
px4_work_queue
surface_vehicle_control
pure_pursuit
MODULE_CONFIG
module.yaml
)
+5
View File
@@ -0,0 +1,5 @@
menuconfig MODULES_BOAT_RUDDER
bool "boat_rudder"
default n
---help---
Enable support for rudder-steered boats
+69
View File
@@ -0,0 +1,69 @@
module_name: Boat Rudder
parameters:
- group: Boat Rudder
definitions:
BR_WHEEL_BASE:
description:
short: Wheel base
long: Distance from the front to the rear axle.
type: float
unit: m
min: 0
max: 100
increment: 0.001
decimal: 3
default: 0
BR_MAX_STR_ANG:
description:
short: Maximum steering angle
type: float
unit: rad
min: 0
max: 1.5708
increment: 0.01
decimal: 2
default: 0
BR_STR_RATE_LIM:
description:
short: Steering rate limit
long: Set to -1 to disable.
type: float
unit: deg/s
min: -1
max: 1000
increment: 0.01
decimal: 2
default: -1
BR_ACC_RAD_MAX:
description:
short: Maximum acceptance radius for the waypoints
long: |
The controller scales the acceptance radius based on the angle between
the previous, current and next waypoint.
Higher value -> smoother trajectory at the cost of how close the rover gets
to the waypoint (Set to -1 to disable corner cutting).
type: float
unit: m
min: -1
max: 100
increment: 0.01
decimal: 2
default: -1
BR_ACC_RAD_GAIN:
description:
short: Tuning parameter for corner cutting
long: |
The geometric ideal acceptance radius is multiplied by this factor
to account for kinematic and dynamic effects.
Higher value -> The rover starts to cut the corner earlier.
type: float
min: 1
max: 100
increment: 0.01
decimal: 2
default: 1
@@ -125,11 +125,13 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed)
if (_flow_counter == 0) {
_flow_vel_body_lpf.reset(_flow_vel_body);
_flow_rate_compensated_lpf.reset(_flow_rate_compensated);
_flow_counter = 1;
} else {
_flow_vel_body_lpf.update(_flow_vel_body);
_flow_rate_compensated_lpf.update(_flow_rate_compensated);
_flow_counter++;
}
@@ -240,8 +242,23 @@ void Ekf::resetTerrainToFlow()
{
ECL_INFO("reset hagl to flow");
// TODO: use the flow data
const float new_terrain = -_gpos.altitude() + _params.ekf2_min_rng;
float new_terrain = -_gpos.altitude() + _params.ekf2_min_rng;
if (isOtherSourceOfHorizontalAidingThan(_control_status.flags.opt_flow)) {
// ||vel_NE|| = ||( R * flow_body * range).xy()||
// range = ||vel_NE|| / ||P * R * flow_body||
constexpr float kProjXY[2][3] = {{1.f, 0.f, 0.f}, {0.f, 1.f, 0.f}};
const matrix::Matrix<float, 2, 3> proj(kProjXY);
const Vector3f flow_body(-_flow_rate_compensated_lpf.getState()(1), _flow_rate_compensated_lpf.getState()(0), 0.f);
const float denom = Vector2f(proj * _R_to_earth * flow_body).norm();
if (denom > 1e-6f) {
const float range = _state.vel.xy().norm() / denom;
new_terrain = -_gpos.altitude() + max(range, _params.ekf2_min_rng);
}
}
const float delta_terrain = new_terrain - _state.terrain;
_state.terrain = new_terrain;
P.uncorrelateCovarianceSetVariance<State::terrain.dof>(State::terrain.idx, 100.f);
+1
View File
@@ -529,6 +529,7 @@ private:
uint32_t _flow_counter{0}; ///< number of flow samples read for initialization
Vector2f _flow_rate_compensated{}; ///< measured angular rate of the image about the X and Y body axes after removal of body rotation (rad/s), RH rotation is positive
AlphaFilter<Vector2f> _flow_rate_compensated_lpf{_dt_ekf_avg, _kSensorLpfTimeConstant};
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_AIRSPEED)
+9 -9
View File
@@ -106,15 +106,15 @@ void LoggedTopics::add_default_topics()
add_topic("position_setpoint_triplet", 200);
add_optional_topic("px4io_status");
add_topic("radio_status");
add_optional_topic("rover_attitude_setpoint", 100);
add_optional_topic("rover_attitude_status", 100);
add_optional_topic("rover_position_setpoint", 100);
add_optional_topic("rover_rate_setpoint", 100);
add_optional_topic("rover_rate_status", 100);
add_optional_topic("rover_speed_setpoint", 100);
add_optional_topic("rover_speed_status", 100);
add_optional_topic("rover_steering_setpoint", 100);
add_optional_topic("rover_throttle_setpoint", 100);
add_optional_topic("surface_vehicle_attitude_setpoint", 100);
add_optional_topic("surface_vehicle_attitude_status", 100);
add_optional_topic("surface_vehicle_position_setpoint", 100);
add_optional_topic("surface_vehicle_rate_setpoint", 100);
add_optional_topic("surface_vehicle_rate_status", 100);
add_optional_topic("surface_vehicle_speed_setpoint", 100);
add_optional_topic("surface_vehicle_speed_status", 100);
add_optional_topic("surface_vehicle_steering_setpoint", 100);
add_optional_topic("surface_vehicle_throttle_setpoint", 100);
add_topic("rtl_time_estimate", 1000);
add_topic("rtl_status", 2000);
add_optional_topic("sensor_airflow", 100);
+23 -1
View File
@@ -55,7 +55,10 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
* Determines when to start and stop logging. By default, logging is started
* when arming the system, and stopped when disarming.
*
* @value -1 disabled
* Note: The logging start/end points that can be configured here only apply to
* SD logging. The mavlink backend is started/stopped independently
* of these points.
*
* @value 0 when armed until disarm (default)
* @value 1 from boot until disarm
* @value 2 from boot until shutdown
@@ -67,6 +70,25 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
*/
PARAM_DEFINE_INT32(SDLOG_MODE, 0);
/**
* Logging Backend (integer bitmask).
*
* If no logging is set the logger will not be started.
*
* Set bits true to enable:
* 0: SD card logging
* 1: Mavlink logging
*
* @min 0
* @max 3
* @bit 0 SD card logging
* @bit 1 Mavlink logging
*
* @reboot_required true
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_BACKEND, 3);
/**
* Battery-only Logging
*
@@ -48,8 +48,8 @@ void AckermannActControl::updateParams()
_servo_setpoint.setSlewRate((M_DEG_TO_RAD_F * _param_ra_str_rate_limit.get()) / _param_ra_max_str_ang.get());
}
if (_param_ro_accel_limit.get() > FLT_EPSILON && _param_ro_max_thr_speed.get() > FLT_EPSILON) {
_motor_setpoint.setSlewRate(_param_ro_accel_limit.get() / _param_ro_max_thr_speed.get());
if (_param_sv_accel_limit.get() > FLT_EPSILON && _param_sv_max_thr_speed.get() > FLT_EPSILON) {
_motor_setpoint.setSlewRate(_param_sv_accel_limit.get() / _param_sv_max_thr_speed.get());
}
}
@@ -60,10 +60,10 @@ void AckermannActControl::updateActControl()
const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 10_ms) * 1e-6f;
// Motor control
if (_rover_throttle_setpoint_sub.updated()) {
rover_throttle_setpoint_s rover_throttle_setpoint{};
_rover_throttle_setpoint_sub.copy(&rover_throttle_setpoint);
_throttle_setpoint = rover_throttle_setpoint.throttle_body_x;
if (_surface_vehicle_throttle_setpoint_sub.updated()) {
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
_surface_vehicle_throttle_setpoint_sub.copy(&surface_vehicle_throttle_setpoint);
_throttle_setpoint = surface_vehicle_throttle_setpoint.throttle_body_x;
}
if (PX4_ISFINITE(_throttle_setpoint)) {
@@ -71,19 +71,19 @@ void AckermannActControl::updateActControl()
_actuator_motors_sub.copy(&actuator_motors_sub);
actuator_motors_s actuator_motors{};
actuator_motors.reversible_flags = _param_r_rev.get();
actuator_motors.control[0] = RoverControl::throttleControl(_motor_setpoint,
_throttle_setpoint, actuator_motors_sub.control[0], _param_ro_accel_limit.get(),
_param_ro_decel_limit.get(), _param_ro_max_thr_speed.get(), dt);
actuator_motors.control[0] = SurfaceVehicleControl::throttleControl(_motor_setpoint,
_throttle_setpoint, actuator_motors_sub.control[0], _param_sv_accel_limit.get(),
_param_sv_decel_limit.get(), _param_sv_max_thr_speed.get(), dt);
actuator_motors.timestamp = _timestamp;
_actuator_motors_pub.publish(actuator_motors);
}
// Servo control
if (_rover_steering_setpoint_sub.updated()) {
rover_steering_setpoint_s rover_steering_setpoint{};
_rover_steering_setpoint_sub.copy(&rover_steering_setpoint);
_steering_setpoint = rover_steering_setpoint.normalized_steering_setpoint;
if (_surface_vehicle_steering_setpoint_sub.updated()) {
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
_surface_vehicle_steering_setpoint_sub.copy(&surface_vehicle_steering_setpoint);
_steering_setpoint = surface_vehicle_steering_setpoint.normalized_steering_setpoint;
}
if (PX4_ISFINITE(_steering_setpoint)) {
@@ -37,7 +37,7 @@
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
@@ -46,8 +46,8 @@
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_throttle_setpoint.h>
/**
* @brief Class for ackermann actuator control.
@@ -63,7 +63,7 @@ public:
~AckermannActControl() = default;
/**
* @brief Generate and publish actuatorMotors/actuatorServos setpoints from roverThrottleSetpoint/roverSteeringSetpoint.
* @brief Generate and publish actuatorMotors/actuatorServos setpoints from SurfaceVehicleThrottleSetpoint/SurfaceVehicleSteeringSetpoint.
*/
void updateActControl();
@@ -83,8 +83,8 @@ private:
// uORB subscriptions
uORB::Subscription _actuator_servos_sub{ORB_ID(actuator_servos)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _rover_steering_setpoint_sub{ORB_ID(rover_steering_setpoint)};
uORB::Subscription _rover_throttle_setpoint_sub{ORB_ID(rover_throttle_setpoint)};
uORB::Subscription _surface_vehicle_steering_setpoint_sub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Subscription _surface_vehicle_throttle_setpoint_sub{ORB_ID(surface_vehicle_throttle_setpoint)};
// uORB publications
uORB::Publication<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
@@ -104,8 +104,8 @@ private:
(ParamInt<px4::params::CA_R_REV>) _param_r_rev,
(ParamFloat<px4::params::RA_STR_RATE_LIM>) _param_ra_str_rate_limit,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_str_ang,
(ParamFloat<px4::params::RO_ACCEL_LIM>) _param_ro_accel_limit,
(ParamFloat<px4::params::RO_DECEL_LIM>) _param_ro_decel_limit,
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed
(ParamFloat<px4::params::SV_ACCEL_LIM>) _param_sv_accel_limit,
(ParamFloat<px4::params::SV_DECEL_LIM>) _param_sv_decel_limit,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed
)
};
@@ -37,8 +37,8 @@ using namespace time_literals;
AckermannAttControl::AckermannAttControl(ModuleParams *parent) : ModuleParams(parent)
{
_rover_rate_setpoint_pub.advertise();
_rover_attitude_status_pub.advertise();
_surface_vehicle_rate_setpoint_pub.advertise();
_surface_vehicle_attitude_status_pub.advertise();
updateParams();
}
@@ -46,12 +46,12 @@ void AckermannAttControl::updateParams()
{
ModuleParams::updateParams();
if (_param_ro_yaw_rate_limit.get() > FLT_EPSILON) {
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
if (_param_sv_yaw_rate_limit.get() > FLT_EPSILON) {
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
// Set up PID controller
_pid_yaw.setGains(_param_ro_yaw_p.get(), 0.f, 0.f);
_pid_yaw.setGains(_param_sv_yaw_p.get(), 0.f, 0.f);
_pid_yaw.setIntegralLimit(0.f);
_pid_yaw.setOutputLimit(_max_yaw_rate);
@@ -73,22 +73,22 @@ void AckermannAttControl::updateAttControl()
_param_ra_wheel_base.get(); // Maximum possible yaw rate at current velocity
float yaw_slew_rate = math::min(max_possible_yaw_rate, _max_yaw_rate);
float yaw_rate_setpoint = RoverControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, yaw_slew_rate,
float yaw_rate_setpoint = SurfaceVehicleControl::attitudeControl(_adjusted_yaw_setpoint, _pid_yaw, yaw_slew_rate,
_vehicle_yaw, _yaw_setpoint, dt);
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = _timestamp;
rover_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate);
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = _timestamp;
surface_vehicle_rate_setpoint.yaw_rate_setpoint = math::constrain(yaw_rate_setpoint, -_max_yaw_rate, _max_yaw_rate);
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
}
// Publish attitude controller status (logging only)
rover_attitude_status_s rover_attitude_status;
rover_attitude_status.timestamp = _timestamp;
rover_attitude_status.measured_yaw = _vehicle_yaw;
rover_attitude_status.adjusted_yaw_setpoint = matrix::wrap_pi(_adjusted_yaw_setpoint.getState());
_rover_attitude_status_pub.publish(rover_attitude_status);
surface_vehicle_attitude_status_s surface_vehicle_attitude_status;
surface_vehicle_attitude_status.timestamp = _timestamp;
surface_vehicle_attitude_status.measured_yaw = _vehicle_yaw;
surface_vehicle_attitude_status.adjusted_yaw_setpoint = matrix::wrap_pi(_adjusted_yaw_setpoint.getState());
_surface_vehicle_attitude_status_pub.publish(surface_vehicle_attitude_status);
}
@@ -106,13 +106,13 @@ void AckermannAttControl::updateSubscriptions()
actuator_motors_s actuator_motors;
_actuator_motors_sub.copy(&actuator_motors);
_estimated_speed_body_x = math::interpolate<float> (actuator_motors.control[0], -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
-_param_sv_max_thr_speed.get(), _param_sv_max_thr_speed.get());
}
if (_rover_attitude_setpoint_sub.updated()) {
rover_attitude_setpoint_s rover_attitude_setpoint{};
_rover_attitude_setpoint_sub.copy(&rover_attitude_setpoint);
_yaw_setpoint = rover_attitude_setpoint.yaw_setpoint;
if (_surface_vehicle_attitude_setpoint_sub.updated()) {
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
_surface_vehicle_attitude_setpoint_sub.copy(&surface_vehicle_attitude_setpoint);
_yaw_setpoint = surface_vehicle_attitude_setpoint.yaw_setpoint;
}
}
@@ -120,7 +120,7 @@ bool AckermannAttControl::runSanityChecks()
{
bool ret = true;
if (_param_ro_max_thr_speed.get() < FLT_EPSILON) {
if (_param_sv_max_thr_speed.get() < FLT_EPSILON) {
ret = false;
}
@@ -132,7 +132,7 @@ bool AckermannAttControl::runSanityChecks()
ret = false;
}
if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) {
if (_param_sv_yaw_rate_limit.get() < FLT_EPSILON) {
ret = false;
}
@@ -37,7 +37,7 @@
#include <px4_platform_common/module_params.h>
// Library includes
#include <lib/rover_control/RoverControl.hpp>
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/pid/PID.hpp>
#include <lib/slew_rate/SlewRateYaw.hpp>
#include <math.h>
@@ -46,10 +46,10 @@
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/rover_attitude_status.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_status.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/actuator_motors.h>
/**
@@ -66,7 +66,7 @@ public:
~AckermannAttControl() = default;
/**
* @brief Generate and publish roverRateSetpoint from roverAttitudeSetpoint.
* @brief Generate and publish SurfaceVehicleRateSetpoint from SurfaceVehicleAttitudeSetpoint.
*/
void updateAttControl();
@@ -96,18 +96,18 @@ private:
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
uORB::Subscription _rover_attitude_setpoint_sub{ORB_ID(rover_attitude_setpoint)};
uORB::Subscription _surface_vehicle_attitude_setpoint_sub{ORB_ID(surface_vehicle_attitude_setpoint)};
// uORB publications
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_attitude_status_s> _rover_attitude_status_pub{ORB_ID(rover_attitude_status)};
uORB::Publication<surface_vehicle_rate_setpoint_s> _surface_vehicle_rate_setpoint_pub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Publication<surface_vehicle_attitude_status_s> _surface_vehicle_attitude_status_pub{ORB_ID(surface_vehicle_attitude_status)};
// Variables
float _vehicle_yaw{0.f};
hrt_abstime _timestamp{0};
float _max_yaw_rate{0.f};
float _estimated_speed_body_x{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed_body_x]
between [0, 0] and [1, _param_ro_max_thr_speed].*/
between [0, 0] and [1, _param_sv_max_thr_speed].*/
float _yaw_setpoint{NAN};
// Controllers
@@ -116,11 +116,11 @@ private:
// Parameters
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::RA_WHEEL_BASE>) _param_ra_wheel_base,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_str_ang,
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_P>) _param_ro_yaw_p,
(ParamFloat<px4::params::RO_YAW_STICK_DZ>) _param_ro_yaw_stick_dz
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_P>) _param_sv_yaw_p,
(ParamFloat<px4::params::SV_YAW_STICK_DZ>) _param_sv_yaw_stick_dz
)
};
@@ -38,13 +38,13 @@ using namespace time_literals;
AckermannAutoMode::AckermannAutoMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_position_setpoint_pub.advertise();
_surface_vehicle_position_setpoint_pub.advertise();
}
void AckermannAutoMode::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
if (_param_ra_wheel_base.get() > FLT_EPSILON && _max_yaw_rate > FLT_EPSILON
&& _param_ra_max_str_ang.get() > FLT_EPSILON) {
@@ -70,17 +70,18 @@ void AckermannAutoMode::autoControl()
updateWaypointsAndAcceptanceRadius();
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = _curr_wp_ned(0);
rover_position_setpoint.position_ned[1] = _curr_wp_ned(1);
rover_position_setpoint.start_ned[0] = _prev_wp_ned(0);
rover_position_setpoint.start_ned[1] = _prev_wp_ned(1);
rover_position_setpoint.arrival_speed = arrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius, _curr_wp_type,
_waypoint_transition_angle, _max_yaw_rate);
rover_position_setpoint.cruising_speed = _cruising_speed;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = _curr_wp_ned(0);
surface_vehicle_position_setpoint.position_ned[1] = _curr_wp_ned(1);
surface_vehicle_position_setpoint.start_ned[0] = _prev_wp_ned(0);
surface_vehicle_position_setpoint.start_ned[1] = _prev_wp_ned(1);
surface_vehicle_position_setpoint.arrival_speed = arrivalSpeed(_cruising_speed, _min_speed, _acceptance_radius,
_curr_wp_type,
_waypoint_transition_angle, _max_yaw_rate);
surface_vehicle_position_setpoint.cruising_speed = _cruising_speed;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
}
}
@@ -91,10 +92,11 @@ void AckermannAutoMode::updateWaypointsAndAcceptanceRadius()
_position_setpoint_triplet_sub.copy(&position_setpoint_triplet);
_curr_wp_type = position_setpoint_triplet.current.type;
RoverControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet,
SurfaceVehicleControl::globalToLocalSetpointTriplet(_curr_wp_ned, _prev_wp_ned, _next_wp_ned, position_setpoint_triplet,
_curr_pos_ned, _global_ned_proj_ref);
_waypoint_transition_angle = RoverControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned, _next_wp_ned);
_waypoint_transition_angle = SurfaceVehicleControl::calcWaypointTransitionAngle(_prev_wp_ned, _curr_wp_ned,
_next_wp_ned);
// Update acceptance radius
if (_param_ra_acc_rad_max.get() >= _param_nav_acc_rad.get()) {
@@ -107,7 +109,7 @@ void AckermannAutoMode::updateWaypointsAndAcceptanceRadius()
// Waypoint cruising speed
_cruising_speed = position_setpoint_triplet.current.cruising_speed > 0.f ? math::constrain(
position_setpoint_triplet.current.cruising_speed, 0.f, _param_ro_speed_limit.get()) : _param_ro_speed_limit.get();
position_setpoint_triplet.current.cruising_speed, 0.f, _param_sv_speed_limit.get()) : _param_sv_speed_limit.get();
}
float AckermannAutoMode::updateAcceptanceRadius(const float waypoint_transition_angle,
@@ -143,11 +145,11 @@ float AckermannAutoMode::arrivalSpeed(const float cruising_speed, const float mi
|| curr_wp_type == position_setpoint_s::SETPOINT_TYPE_IDLE) {
return 0.f; // Stop at the waypoint
} else if (_param_ro_speed_red.get() > FLT_EPSILON) {
const float speed_reduction = math::constrain(_param_ro_speed_red.get() * math::interpolate(
} else if (_param_sv_speed_red.get() > FLT_EPSILON) {
const float speed_reduction = math::constrain(_param_sv_speed_red.get() * math::interpolate(
M_PI_F - waypoint_transition_angle,
0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f);
return math::constrain(_param_ro_max_thr_speed.get() * (1.f - speed_reduction), min_speed,
return math::constrain(_param_sv_max_thr_speed.get() * (1.f - speed_reduction), min_speed,
cruising_speed); // Slow down for cornering
}
@@ -37,7 +37,7 @@
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <math.h>
// uORB includes
@@ -46,7 +46,7 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/position_controller_status.h>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
/**
* @brief Class for ackermann auto mode.
@@ -62,7 +62,7 @@ public:
~AckermannAutoMode() = default;
/**
* @brief Generate and publish roverPositionSetpoint from positionSetpointTriplet.
* @brief Generate and publish SurfaceVehiclePositionSetpoint from positionSetpointTriplet.
*/
void autoControl();
@@ -110,7 +110,7 @@ private:
uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)};
// uORB publications
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Publication<position_controller_status_s> _position_controller_status_pub{ORB_ID(position_controller_status)};
// Variables
@@ -127,14 +127,14 @@ private:
int _curr_wp_type{position_setpoint_s::SETPOINT_TYPE_IDLE};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_SPEED_LIM>) _param_ro_speed_limit,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit,
(ParamFloat<px4::params::RA_WHEEL_BASE>) _param_ra_wheel_base,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_str_ang,
(ParamFloat<px4::params::NAV_ACC_RAD>) _param_nav_acc_rad,
(ParamFloat<px4::params::RA_ACC_RAD_MAX>) _param_ra_acc_rad_max,
(ParamFloat<px4::params::RA_ACC_RAD_GAIN>) _param_ra_acc_rad_gain,
(ParamFloat<px4::params::RO_SPEED_RED>) _param_ro_speed_red,
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed
(ParamFloat<px4::params::SV_SPEED_RED>) _param_sv_speed_red,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed
)
};
@@ -38,50 +38,50 @@ using namespace time_literals;
AckermannManualMode::AckermannManualMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_throttle_setpoint_pub.advertise();
_rover_steering_setpoint_pub.advertise();
_rover_rate_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_rover_speed_setpoint_pub.advertise();
_rover_position_setpoint_pub.advertise();
_surface_vehicle_throttle_setpoint_pub.advertise();
_surface_vehicle_steering_setpoint_pub.advertise();
_surface_vehicle_rate_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_position_setpoint_pub.advertise();
}
void AckermannManualMode::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
}
void AckermannManualMode::manual()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = hrt_absolute_time();
rover_steering_setpoint.normalized_steering_setpoint = manual_control_setpoint.roll;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = 0.f;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_steering_setpoint.normalized_steering_setpoint = manual_control_setpoint.roll;
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
}
void AckermannManualMode::acro()
{
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = 0.f;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>
(manual_control_setpoint.roll, _param_ro_yaw_expo.get(), _param_ro_yaw_supexpo.get());
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>
(manual_control_setpoint.roll, _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
}
void AckermannManualMode::stab()
@@ -95,39 +95,39 @@ void AckermannManualMode::stab()
manual_control_setpoint_s manual_control_setpoint{};
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
rover_throttle_setpoint_s rover_throttle_setpoint{};
rover_throttle_setpoint.timestamp = hrt_absolute_time();
rover_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
rover_throttle_setpoint.throttle_body_y = 0.f;
_rover_throttle_setpoint_pub.publish(rover_throttle_setpoint);
surface_vehicle_throttle_setpoint_s surface_vehicle_throttle_setpoint{};
surface_vehicle_throttle_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_throttle_setpoint.throttle_body_x = manual_control_setpoint.throttle;
surface_vehicle_throttle_setpoint.throttle_body_y = 0.f;
_surface_vehicle_throttle_setpoint_pub.publish(surface_vehicle_throttle_setpoint);
if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON
|| fabsf(rover_throttle_setpoint.throttle_body_x) < FLT_EPSILON) {
|| fabsf(surface_vehicle_throttle_setpoint.throttle_body_x) < FLT_EPSILON) {
_stab_yaw_setpoint = NAN;
// Rate control
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_ro_yaw_stick_dz.get()), _param_ro_yaw_expo.get(), _param_ro_yaw_supexpo.get());
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_sv_yaw_stick_dz.get()), _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
// Set uncontrolled setpoint invalid
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = NAN;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = NAN;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
} else { // Heading control
if (!PX4_ISFINITE(_stab_yaw_setpoint)) {
_stab_yaw_setpoint = _vehicle_yaw;
}
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = _stab_yaw_setpoint;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
}
}
@@ -157,42 +157,42 @@ void AckermannManualMode::position()
_manual_control_setpoint_sub.copy(&manual_control_setpoint);
const float speed_setpoint = math::interpolate<float>(manual_control_setpoint.throttle,
-1.f, 1.f, -_param_ro_speed_limit.get(), _param_ro_speed_limit.get());
-1.f, 1.f, -_param_sv_speed_limit.get(), _param_sv_speed_limit.get());
if (fabsf(manual_control_setpoint.roll) > FLT_EPSILON
|| fabsf(speed_setpoint) < FLT_EPSILON) {
_pos_ctl_course_direction = Vector2f(NAN, NAN);
// Speed control
rover_speed_setpoint_s rover_speed_setpoint{};
rover_speed_setpoint.timestamp = hrt_absolute_time();
rover_speed_setpoint.speed_body_x = speed_setpoint;
_rover_speed_setpoint_pub.publish(rover_speed_setpoint);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_speed_setpoint.speed_body_x = speed_setpoint;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
// Rate control
rover_rate_setpoint_s rover_rate_setpoint{};
rover_rate_setpoint.timestamp = hrt_absolute_time();
rover_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_ro_yaw_stick_dz.get()), _param_ro_yaw_expo.get(), _param_ro_yaw_supexpo.get());
_rover_rate_setpoint_pub.publish(rover_rate_setpoint);
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
surface_vehicle_rate_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_rate_setpoint.yaw_rate_setpoint = matrix::sign(manual_control_setpoint.throttle) * _max_yaw_rate *
math::superexpo<float>(math::deadzone(manual_control_setpoint.roll,
_param_sv_yaw_stick_dz.get()), _param_sv_yaw_expo.get(), _param_sv_yaw_supexpo.get());
_surface_vehicle_rate_setpoint_pub.publish(surface_vehicle_rate_setpoint);
// Set uncontrolled setpoints invalid
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = NAN;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = NAN;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = NAN;
rover_position_setpoint.position_ned[1] = NAN;
rover_position_setpoint.start_ned[0] = NAN;
rover_position_setpoint.start_ned[1] = NAN;
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.cruising_speed = NAN;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = NAN;
surface_vehicle_position_setpoint.position_ned[1] = NAN;
surface_vehicle_position_setpoint.start_ned[0] = NAN;
surface_vehicle_position_setpoint.start_ned[1] = NAN;
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.cruising_speed = NAN;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
} else { // Course control
if (!_pos_ctl_course_direction.isAllFinite()) {
@@ -205,16 +205,16 @@ void AckermannManualMode::position()
const float vector_scaling = fabsf(start_to_curr_pos * _pos_ctl_course_direction) + _param_pp_lookahd_max.get();
const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign(speed_setpoint) *
vector_scaling * _pos_ctl_course_direction;
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = target_waypoint_ned(0);
rover_position_setpoint.position_ned[1] = target_waypoint_ned(1);
rover_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0);
rover_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1);
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.cruising_speed = speed_setpoint;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = target_waypoint_ned(0);
surface_vehicle_position_setpoint.position_ned[1] = target_waypoint_ned(1);
surface_vehicle_position_setpoint.start_ned[0] = _pos_ctl_start_position_ned(0);
surface_vehicle_position_setpoint.start_ned[1] = _pos_ctl_start_position_ned(1);
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.cruising_speed = speed_setpoint;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
}
}
@@ -37,7 +37,7 @@
#include <px4_platform_common/module_params.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <math.h>
// uORB includes
@@ -47,12 +47,12 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/rover_throttle_setpoint.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/rover_speed_setpoint.h>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/surface_vehicle_throttle_setpoint.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
/**
* @brief Class for ackermann manual mode.
@@ -68,22 +68,22 @@ public:
~AckermannManualMode() = default;
/**
* @brief Publish roverThrottleSetpoint and roverSteeringSetpoint from manualControlSetpoint.
* @brief Publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleSteeringSetpoint from manualControlSetpoint.
*/
void manual();
/**
* @brief Generate and publish roverThrottleSetpoint and RoverRateSetpoint from manualControlSetpoint.
* @brief Generate and publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleRateSetpoint from manualControlSetpoint.
*/
void acro();
/**
* @brief Generate and publish roverThrottleSetpoint and RoverAttitudeSetpoint from manualControlSetpoint.
* @brief Generate and publish SurfaceVehicleThrottleSetpoint and SurfaceVehicleAttitudeSetpoint from manualControlSetpoint.
*/
void stab();
/**
* @brief Generate and publish roverSpeedSetpoint/roverRateSetpoint or roverPositionSetpoint from manualControlSetpoint.
* @brief Generate and publish SurfaceVehicleSpeedSetpoint/SurfaceVehicleRateSetpoint or SurfaceVehiclePositionSetpoint from manualControlSetpoint.
*/
void position();
@@ -105,12 +105,12 @@ private:
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
// uORB publications
uORB::Publication<rover_throttle_setpoint_s> _rover_throttle_setpoint_pub{ORB_ID(rover_throttle_setpoint)};
uORB::Publication<rover_steering_setpoint_s> _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)};
uORB::Publication<rover_rate_setpoint_s> _rover_rate_setpoint_pub{ORB_ID(rover_rate_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<rover_speed_setpoint_s> _rover_speed_setpoint_pub{ORB_ID(rover_speed_setpoint)};
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
uORB::Publication<surface_vehicle_throttle_setpoint_s> _surface_vehicle_throttle_setpoint_pub{ORB_ID(surface_vehicle_throttle_setpoint)};
uORB::Publication<surface_vehicle_steering_setpoint_s> _surface_vehicle_steering_setpoint_pub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Publication<surface_vehicle_rate_setpoint_s> _surface_vehicle_rate_setpoint_pub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
// Variables
MapProjection _global_ned_proj_ref{}; // Transform global to NED coordinates
@@ -123,12 +123,12 @@ private:
float _max_yaw_rate{NAN};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_P>) _param_ro_yaw_p,
(ParamFloat<px4::params::RO_YAW_STICK_DZ>) _param_ro_yaw_stick_dz,
(ParamFloat<px4::params::RO_YAW_EXPO>) _param_ro_yaw_expo,
(ParamFloat<px4::params::RO_YAW_SUPEXPO>) _param_ro_yaw_supexpo,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_P>) _param_sv_yaw_p,
(ParamFloat<px4::params::SV_YAW_STICK_DZ>) _param_sv_yaw_stick_dz,
(ParamFloat<px4::params::SV_YAW_EXPO>) _param_sv_yaw_expo,
(ParamFloat<px4::params::SV_YAW_SUPEXPO>) _param_sv_yaw_supexpo,
(ParamFloat<px4::params::PP_LOOKAHD_MAX>) _param_pp_lookahd_max,
(ParamFloat<px4::params::RO_SPEED_LIM>) _param_ro_speed_limit
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit
)
};
@@ -38,9 +38,9 @@ using namespace time_literals;
AckermannOffboardMode::AckermannOffboardMode(ModuleParams *parent) : ModuleParams(parent)
{
updateParams();
_rover_speed_setpoint_pub.advertise();
_rover_position_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_position_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
}
void AckermannOffboardMode::updateParams()
@@ -57,26 +57,26 @@ void AckermannOffboardMode::offboardControl()
_trajectory_setpoint_sub.copy(&trajectory_setpoint);
if (offboard_control_mode.position) {
rover_position_setpoint_s rover_position_setpoint{};
rover_position_setpoint.timestamp = hrt_absolute_time();
rover_position_setpoint.position_ned[0] = trajectory_setpoint.position[0];
rover_position_setpoint.position_ned[1] = trajectory_setpoint.position[1];
rover_position_setpoint.start_ned[0] = NAN;
rover_position_setpoint.start_ned[1] = NAN;
rover_position_setpoint.cruising_speed = NAN;
rover_position_setpoint.arrival_speed = NAN;
rover_position_setpoint.yaw = NAN;
_rover_position_setpoint_pub.publish(rover_position_setpoint);
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint{};
surface_vehicle_position_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_position_setpoint.position_ned[0] = trajectory_setpoint.position[0];
surface_vehicle_position_setpoint.position_ned[1] = trajectory_setpoint.position[1];
surface_vehicle_position_setpoint.start_ned[0] = NAN;
surface_vehicle_position_setpoint.start_ned[1] = NAN;
surface_vehicle_position_setpoint.cruising_speed = NAN;
surface_vehicle_position_setpoint.arrival_speed = NAN;
surface_vehicle_position_setpoint.yaw = NAN;
_surface_vehicle_position_setpoint_pub.publish(surface_vehicle_position_setpoint);
} else if (offboard_control_mode.velocity) {
const Vector2f velocity_ned(trajectory_setpoint.velocity[0], trajectory_setpoint.velocity[1]);
rover_speed_setpoint_s rover_speed_setpoint{};
rover_speed_setpoint.timestamp = hrt_absolute_time();
rover_speed_setpoint.speed_body_x = velocity_ned.norm();
_rover_speed_setpoint_pub.publish(rover_speed_setpoint);
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = hrt_absolute_time();
rover_attitude_setpoint.yaw_setpoint = atan2f(velocity_ned(1), velocity_ned(0));
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_speed_setpoint.speed_body_x = velocity_ned.norm();
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = hrt_absolute_time();
surface_vehicle_attitude_setpoint.yaw_setpoint = atan2f(velocity_ned(1), velocity_ned(0));
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
}
}
@@ -43,9 +43,9 @@
// uORB includes
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/rover_speed_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/trajectory_setpoint.h>
@@ -81,7 +81,7 @@ private:
uORB::Subscription _offboard_control_mode_sub{ORB_ID(offboard_control_mode)};
// uORB publications
uORB::Publication<rover_speed_setpoint_s> _rover_speed_setpoint_pub{ORB_ID(rover_speed_setpoint)};
uORB::Publication<rover_position_setpoint_s> _rover_position_setpoint_pub{ORB_ID(rover_position_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_position_setpoint_s> _surface_vehicle_position_setpoint_pub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
};
@@ -38,8 +38,8 @@ using namespace time_literals;
AckermannPosControl::AckermannPosControl(ModuleParams *parent) : ModuleParams(parent)
{
_pure_pursuit_status_pub.advertise();
_rover_speed_setpoint_pub.advertise();
_rover_attitude_setpoint_pub.advertise();
_surface_vehicle_speed_setpoint_pub.advertise();
_surface_vehicle_attitude_setpoint_pub.advertise();
updateParams();
}
@@ -47,7 +47,7 @@ AckermannPosControl::AckermannPosControl(ModuleParams *parent) : ModuleParams(pa
void AckermannPosControl::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_min_speed = _param_ra_wheel_base.get() * _max_yaw_rate / tanf(_param_ra_max_str_ang.get());
}
@@ -67,8 +67,8 @@ void AckermannPosControl::updatePosControl()
if (distance_to_target > _acceptance_radius || _arrival_speed > FLT_EPSILON) {
float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_ro_jerk_limit.get(),
_param_ro_decel_limit.get(), distance_to_target, fabsf(_arrival_speed));
float speed_setpoint = math::trajectory::computeMaxSpeedFromDistance(_param_sv_jerk_limit.get(),
_param_sv_decel_limit.get(), distance_to_target, fabsf(_arrival_speed));
speed_setpoint = math::min(speed_setpoint, _cruising_speed);
pure_pursuit_status_s pure_pursuit_status{};
@@ -78,35 +78,35 @@ void AckermannPosControl::updatePosControl()
_param_pp_lookahd_max.get(), _param_pp_lookahd_min.get(), _target_waypoint_ned, _start_ned,
_curr_pos_ned, fabsf(speed_setpoint));
if (_param_ro_speed_red.get() > FLT_EPSILON) {
if (_param_sv_speed_red.get() > FLT_EPSILON) {
const float course_error = fabsf(matrix::wrap_pi(bearing_setpoint - _vehicle_yaw));
const float speed_reduction = math::constrain(_param_ro_speed_red.get() * math::interpolate(course_error,
const float speed_reduction = math::constrain(_param_sv_speed_red.get() * math::interpolate(course_error,
0.f, M_PI_F, 0.f, 1.f), 0.f, 1.f);
const float max_speed = math::constrain(_param_ro_max_thr_speed.get() * (1.f - speed_reduction), _min_speed,
_param_ro_max_thr_speed.get());
const float max_speed = math::constrain(_param_sv_max_thr_speed.get() * (1.f - speed_reduction), _min_speed,
_param_sv_max_thr_speed.get());
speed_setpoint = math::constrain(speed_setpoint, -max_speed, max_speed);
}
_pure_pursuit_status_pub.publish(pure_pursuit_status);
rover_speed_setpoint_s rover_speed_setpoint{};
rover_speed_setpoint.timestamp = timestamp;
rover_speed_setpoint.speed_body_x = speed_setpoint;
_rover_speed_setpoint_pub.publish(rover_speed_setpoint);
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = timestamp;
rover_attitude_setpoint.yaw_setpoint = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi(
bearing_setpoint + M_PI_F);
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = timestamp;
surface_vehicle_speed_setpoint.speed_body_x = speed_setpoint;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = timestamp;
surface_vehicle_attitude_setpoint.yaw_setpoint = speed_setpoint > -FLT_EPSILON ? bearing_setpoint : matrix::wrap_pi(
bearing_setpoint + M_PI_F);
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
} else {
rover_speed_setpoint_s rover_speed_setpoint{};
rover_speed_setpoint.timestamp = timestamp;
rover_speed_setpoint.speed_body_x = 0.f;
_rover_speed_setpoint_pub.publish(rover_speed_setpoint);
rover_attitude_setpoint_s rover_attitude_setpoint{};
rover_attitude_setpoint.timestamp = timestamp;
rover_attitude_setpoint.yaw_setpoint = _vehicle_yaw;
_rover_attitude_setpoint_pub.publish(rover_attitude_setpoint);
surface_vehicle_speed_setpoint_s surface_vehicle_speed_setpoint{};
surface_vehicle_speed_setpoint.timestamp = timestamp;
surface_vehicle_speed_setpoint.speed_body_x = 0.f;
_surface_vehicle_speed_setpoint_pub.publish(surface_vehicle_speed_setpoint);
surface_vehicle_attitude_setpoint_s surface_vehicle_attitude_setpoint{};
surface_vehicle_attitude_setpoint.timestamp = timestamp;
surface_vehicle_attitude_setpoint.yaw_setpoint = _vehicle_yaw;
_surface_vehicle_attitude_setpoint_pub.publish(surface_vehicle_attitude_setpoint);
if (!_stopped && fabsf(_vehicle_speed) < FLT_EPSILON) {
_stopped = true;
@@ -144,18 +144,21 @@ void AckermannPosControl::updateSubscriptions()
Vector3f velocity_ned(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz);
Vector3f velocity_xyz = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_ned);
Vector2f velocity_2d = Vector2f(velocity_xyz(0), velocity_xyz(1));
_vehicle_speed = velocity_2d.norm() > _param_ro_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f;
_vehicle_speed = velocity_2d.norm() > _param_sv_speed_th.get() ? sign(velocity_2d(0)) * velocity_2d.norm() : 0.f;
}
if (_rover_position_setpoint_sub.updated()) {
rover_position_setpoint_s rover_position_setpoint;
_rover_position_setpoint_sub.copy(&rover_position_setpoint);
_start_ned = Vector2f(rover_position_setpoint.start_ned[0], rover_position_setpoint.start_ned[1]);
if (_surface_vehicle_position_setpoint_sub.updated()) {
surface_vehicle_position_setpoint_s surface_vehicle_position_setpoint;
_surface_vehicle_position_setpoint_sub.copy(&surface_vehicle_position_setpoint);
_start_ned = Vector2f(surface_vehicle_position_setpoint.start_ned[0], surface_vehicle_position_setpoint.start_ned[1]);
_start_ned = _start_ned.isAllFinite() ? _start_ned : _curr_pos_ned;
_arrival_speed = PX4_ISFINITE(rover_position_setpoint.arrival_speed) ? rover_position_setpoint.arrival_speed : 0.f;
_cruising_speed = PX4_ISFINITE(rover_position_setpoint.cruising_speed) ? rover_position_setpoint.cruising_speed :
_param_ro_speed_limit.get();
_target_waypoint_ned = Vector2f(rover_position_setpoint.position_ned[0], rover_position_setpoint.position_ned[1]);
_arrival_speed = PX4_ISFINITE(surface_vehicle_position_setpoint.arrival_speed) ?
surface_vehicle_position_setpoint.arrival_speed : 0.f;
_cruising_speed = PX4_ISFINITE(surface_vehicle_position_setpoint.cruising_speed) ?
surface_vehicle_position_setpoint.cruising_speed :
_param_sv_speed_limit.get();
_target_waypoint_ned = Vector2f(surface_vehicle_position_setpoint.position_ned[0],
surface_vehicle_position_setpoint.position_ned[1]);
_stopped = false;
}
@@ -165,7 +168,7 @@ bool AckermannPosControl::runSanityChecks()
{
bool ret = true;
if (_param_ro_speed_limit.get() < FLT_EPSILON) {
if (_param_sv_speed_limit.get() < FLT_EPSILON) {
ret = false;
}
@@ -45,9 +45,9 @@
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_position_setpoint.h>
#include <uORB/topics/rover_speed_setpoint.h>
#include <uORB/topics/rover_attitude_setpoint.h>
#include <uORB/topics/surface_vehicle_position_setpoint.h>
#include <uORB/topics/surface_vehicle_speed_setpoint.h>
#include <uORB/topics/surface_vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/position_controller_status.h>
@@ -69,7 +69,7 @@ public:
~AckermannPosControl() = default;
/**
* @brief Generate and publish roverSpeedSetpoint and roverAttitudeSetpoint from roverPositionSetpoint.
* @brief Generate and publish SurfaceVehicleSpeedSetpoint and SurfaceVehicleAttitudeSetpoint from SurfaceVehiclePositionSetpoint.
*/
void updatePosControl();
@@ -82,7 +82,7 @@ public:
/**
* @brief Reset position controller.
*/
void reset() {_start_ned = Vector2f{NAN, NAN}; _target_waypoint_ned = Vector2f{NAN, NAN}; _arrival_speed = 0.f; _cruising_speed = _param_ro_speed_limit.get(); _stopped = false;};
void reset() {_start_ned = Vector2f{NAN, NAN}; _target_waypoint_ned = Vector2f{NAN, NAN}; _arrival_speed = 0.f; _cruising_speed = _param_sv_speed_limit.get(); _stopped = false;};
protected:
/**
@@ -99,12 +99,12 @@ private:
// uORB subscriptions
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)};
uORB::Subscription _rover_position_setpoint_sub{ORB_ID(rover_position_setpoint)};
uORB::Subscription _surface_vehicle_position_setpoint_sub{ORB_ID(surface_vehicle_position_setpoint)};
uORB::Subscription _position_controller_status_sub{ORB_ID(position_controller_status)};
// uORB publications
uORB::Publication<rover_speed_setpoint_s> _rover_speed_setpoint_pub{ORB_ID(rover_speed_setpoint)};
uORB::Publication<rover_attitude_setpoint_s> _rover_attitude_setpoint_pub{ORB_ID(rover_attitude_setpoint)};
uORB::Publication<surface_vehicle_speed_setpoint_s> _surface_vehicle_speed_setpoint_pub{ORB_ID(surface_vehicle_speed_setpoint)};
uORB::Publication<surface_vehicle_attitude_setpoint_s> _surface_vehicle_attitude_setpoint_pub{ORB_ID(surface_vehicle_attitude_setpoint)};
uORB::Publication<pure_pursuit_status_s> _pure_pursuit_status_pub{ORB_ID(pure_pursuit_status)};
// Variables
@@ -124,17 +124,17 @@ private:
uint8_t _updated_reset_counter{0}; /**< counter for estimator resets in xy-direction */
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed,
(ParamFloat<px4::params::RO_SPEED_RED>) _param_ro_speed_red,
(ParamFloat<px4::params::RO_DECEL_LIM>) _param_ro_decel_limit,
(ParamFloat<px4::params::RO_JERK_LIM>) _param_ro_jerk_limit,
(ParamFloat<px4::params::RO_SPEED_LIM>) _param_ro_speed_limit,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::SV_SPEED_RED>) _param_sv_speed_red,
(ParamFloat<px4::params::SV_DECEL_LIM>) _param_sv_decel_limit,
(ParamFloat<px4::params::SV_JERK_LIM>) _param_sv_jerk_limit,
(ParamFloat<px4::params::SV_SPEED_LIM>) _param_sv_speed_limit,
(ParamFloat<px4::params::PP_LOOKAHD_GAIN>) _param_pp_lookahd_gain,
(ParamFloat<px4::params::PP_LOOKAHD_MAX>) _param_pp_lookahd_max,
(ParamFloat<px4::params::PP_LOOKAHD_MIN>) _param_pp_lookahd_min,
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::RA_WHEEL_BASE>) _param_ra_wheel_base,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_str_ang,
(ParamFloat<px4::params::RO_SPEED_TH>) _param_ro_speed_th
(ParamFloat<px4::params::SV_SPEED_TH>) _param_sv_speed_th
)
};
@@ -37,23 +37,23 @@ using namespace time_literals;
AckermannRateControl::AckermannRateControl(ModuleParams *parent) : ModuleParams(parent)
{
_rover_steering_setpoint_pub.advertise();
_rover_rate_status_pub.advertise();
_surface_vehicle_steering_setpoint_pub.advertise();
_surface_vehicle_rate_status_pub.advertise();
updateParams();
}
void AckermannRateControl::updateParams()
{
ModuleParams::updateParams();
_max_yaw_rate = _param_ro_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
_max_yaw_rate = _param_sv_yaw_rate_limit.get() * M_DEG_TO_RAD_F;
// Set up PID controller
_pid_yaw_rate.setGains(_param_ro_yaw_rate_p.get(), _param_ro_yaw_rate_i.get(), 0.f);
_pid_yaw_rate.setGains(_param_sv_yaw_rate_p.get(), _param_sv_yaw_rate_i.get(), 0.f);
_pid_yaw_rate.setIntegralLimit(1.f);
_pid_yaw_rate.setOutputLimit(1.f);
// Set up slew rate
_adjusted_yaw_rate_setpoint.setSlewRate(_param_ro_yaw_accel_limit.get() * M_DEG_TO_RAD_F);
_adjusted_yaw_rate_setpoint.setSlewRate(_param_sv_yaw_accel_limit.get() * M_DEG_TO_RAD_F);
}
void AckermannRateControl::updateRateControl()
@@ -73,7 +73,7 @@ void AckermannRateControl::updateRateControl()
float yaw_rate_limit = math::min(max_possible_yaw_rate, _max_yaw_rate);
float constrained_yaw_rate = math::constrain(_yaw_rate_setpoint, -yaw_rate_limit, yaw_rate_limit);
if (_param_ro_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured
if (_param_sv_yaw_accel_limit.get() > FLT_EPSILON) { // Apply slew rate if configured
if (fabsf(_adjusted_yaw_rate_setpoint.getState() - _vehicle_yaw_rate) > fabsf(constrained_yaw_rate -
_vehicle_yaw_rate)) {
_adjusted_yaw_rate_setpoint.setForcedValue(_vehicle_yaw_rate);
@@ -87,7 +87,7 @@ void AckermannRateControl::updateRateControl()
// Feed forward
steering_setpoint = atanf(_adjusted_yaw_rate_setpoint.getState() * _param_ra_wheel_base.get() / _estimated_speed) *
_param_ro_yaw_rate_corr.get();
_param_sv_yaw_rate_corr.get();
// Feedback (Only when driving forwards because backwards driving is NMP and can introduce instability)
if (_estimated_speed > FLT_EPSILON) {
@@ -95,29 +95,29 @@ void AckermannRateControl::updateRateControl()
steering_setpoint += _pid_yaw_rate.update(_vehicle_yaw_rate, dt);
}
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = _timestamp;
rover_steering_setpoint.normalized_steering_setpoint = math::interpolate<float>(steering_setpoint,
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = _timestamp;
surface_vehicle_steering_setpoint.normalized_steering_setpoint = math::interpolate<float>(steering_setpoint,
-_param_ra_max_str_ang.get(), _param_ra_max_str_ang.get(), -1.f, 1.f); // Normalize steering setpoint
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
} else {
_pid_yaw_rate.resetIntegral();
rover_steering_setpoint_s rover_steering_setpoint{};
rover_steering_setpoint.timestamp = _timestamp;
rover_steering_setpoint.normalized_steering_setpoint = 0.f;
_rover_steering_setpoint_pub.publish(rover_steering_setpoint);
surface_vehicle_steering_setpoint_s surface_vehicle_steering_setpoint{};
surface_vehicle_steering_setpoint.timestamp = _timestamp;
surface_vehicle_steering_setpoint.normalized_steering_setpoint = 0.f;
_surface_vehicle_steering_setpoint_pub.publish(surface_vehicle_steering_setpoint);
}
}
// Publish rate controller status (logging only)
rover_rate_status_s rover_rate_status;
rover_rate_status.timestamp = _timestamp;
rover_rate_status.measured_yaw_rate = _vehicle_yaw_rate;
rover_rate_status.adjusted_yaw_rate_setpoint = _adjusted_yaw_rate_setpoint.getState();
rover_rate_status.pid_yaw_rate_integral = _pid_yaw_rate.getIntegral();
_rover_rate_status_pub.publish(rover_rate_status);
surface_vehicle_rate_status_s surface_vehicle_rate_status;
surface_vehicle_rate_status.timestamp = _timestamp;
surface_vehicle_rate_status.measured_yaw_rate = _vehicle_yaw_rate;
surface_vehicle_rate_status.adjusted_yaw_rate_setpoint = _adjusted_yaw_rate_setpoint.getState();
surface_vehicle_rate_status.pid_yaw_rate_integral = _pid_yaw_rate.getIntegral();
_surface_vehicle_rate_status_pub.publish(surface_vehicle_rate_status);
}
@@ -126,7 +126,7 @@ void AckermannRateControl::updateSubscriptions()
if (_vehicle_angular_velocity_sub.updated()) {
vehicle_angular_velocity_s vehicle_angular_velocity{};
_vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity);
_vehicle_yaw_rate = fabsf(vehicle_angular_velocity.xyz[2]) > _param_ro_yaw_rate_th.get() * M_DEG_TO_RAD_F ?
_vehicle_yaw_rate = fabsf(vehicle_angular_velocity.xyz[2]) > _param_sv_yaw_rate_th.get() * M_DEG_TO_RAD_F ?
vehicle_angular_velocity.xyz[2] : 0.f;
}
@@ -135,14 +135,14 @@ void AckermannRateControl::updateSubscriptions()
actuator_motors_s actuator_motors;
_actuator_motors_sub.copy(&actuator_motors);
_estimated_speed = math::interpolate<float>(actuator_motors.control[0], -1.f, 1.f,
-_param_ro_max_thr_speed.get(), _param_ro_max_thr_speed.get());
_estimated_speed = fabsf(_estimated_speed) > _param_ro_speed_th.get() ? _estimated_speed : 0.f;
-_param_sv_max_thr_speed.get(), _param_sv_max_thr_speed.get());
_estimated_speed = fabsf(_estimated_speed) > _param_sv_speed_th.get() ? _estimated_speed : 0.f;
}
if (_rover_rate_setpoint_sub.updated()) {
rover_rate_setpoint_s rover_rate_setpoint{};
_rover_rate_setpoint_sub.copy(&rover_rate_setpoint);
_yaw_rate_setpoint = rover_rate_setpoint.yaw_rate_setpoint;
if (_surface_vehicle_rate_setpoint_sub.updated()) {
surface_vehicle_rate_setpoint_s surface_vehicle_rate_setpoint{};
_surface_vehicle_rate_setpoint_sub.copy(&surface_vehicle_rate_setpoint);
_yaw_rate_setpoint = surface_vehicle_rate_setpoint.yaw_rate_setpoint;
}
}
@@ -150,10 +150,10 @@ bool AckermannRateControl::runSanityChecks()
{
bool ret = true;
if (_param_ro_max_thr_speed.get() < FLT_EPSILON) {
if (_param_sv_max_thr_speed.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("ackermann_rate_control_conf_invalid_max_thr_speed"), events::Log::Error,
"Invalid configuration of necessary parameter RO_MAX_THR_SPEED", _param_ro_max_thr_speed.get());
"Invalid configuration of necessary parameter SV_MAX_THR_SPEED", _param_sv_max_thr_speed.get());
}
@@ -171,10 +171,10 @@ bool AckermannRateControl::runSanityChecks()
}
if (_param_ro_yaw_rate_limit.get() < FLT_EPSILON) {
if (_param_sv_yaw_rate_limit.get() < FLT_EPSILON) {
ret = false;
events::send<float>(events::ID("ackermann_rate_control_conf_invalid_yaw_rate_lim"), events::Log::Error,
"Invalid configuration of necessary parameter RO_YAW_RATE_LIM", _param_ro_yaw_rate_limit.get());
"Invalid configuration of necessary parameter SV_YAW_RATE_LIM", _param_sv_yaw_rate_limit.get());
}
@@ -38,7 +38,7 @@
#include <px4_platform_common/events.h>
// Libraries
#include <lib/rover_control/RoverControl.hpp>
#include <lib/surface_vehicle_control/SurfaceVehicleControl.hpp>
#include <lib/pid/PID.hpp>
#include <lib/slew_rate/SlewRate.hpp>
#include <math.h>
@@ -46,10 +46,10 @@
// uORB includes
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rover_rate_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_setpoint.h>
#include <uORB/topics/vehicle_angular_velocity.h>
#include <uORB/topics/rover_steering_setpoint.h>
#include <uORB/topics/rover_rate_status.h>
#include <uORB/topics/surface_vehicle_steering_setpoint.h>
#include <uORB/topics/surface_vehicle_rate_status.h>
#include <uORB/topics/actuator_motors.h>
/**
@@ -66,7 +66,7 @@ public:
~AckermannRateControl() = default;
/**
* @brief Generate and publish roverSteeringSetpoint from roverRateSetpoint.
* @brief Generate and publish SurfaceVehicleSteeringSetpoint from SurfaceVehicleRateSetpoint.
*/
void updateRateControl();
@@ -94,17 +94,17 @@ private:
void updateSubscriptions();
// uORB subscriptions
uORB::Subscription _rover_rate_setpoint_sub{ORB_ID(rover_rate_setpoint)};
uORB::Subscription _surface_vehicle_rate_setpoint_sub{ORB_ID(surface_vehicle_rate_setpoint)};
uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)};
uORB::Subscription _actuator_motors_sub{ORB_ID(actuator_motors)};
// uORB publications
uORB::Publication<rover_steering_setpoint_s> _rover_steering_setpoint_pub{ORB_ID(rover_steering_setpoint)};
uORB::Publication<rover_rate_status_s> _rover_rate_status_pub{ORB_ID(rover_rate_status)};
uORB::Publication<surface_vehicle_steering_setpoint_s> _surface_vehicle_steering_setpoint_pub{ORB_ID(surface_vehicle_steering_setpoint)};
uORB::Publication<surface_vehicle_rate_status_s> _surface_vehicle_rate_status_pub{ORB_ID(surface_vehicle_rate_status)};
// Variables
float _estimated_speed{0.f}; /*Vehicle speed estimated by interpolating [actuatorMotorSetpoint, _estimated_speed]
between [0, 0] and [1, _param_ro_max_thr_speed].*/
between [0, 0] and [1, _param_sv_max_thr_speed].*/
float _max_yaw_rate{0.f};
float _vehicle_yaw_rate{0.f};
float _yaw_rate_setpoint{NAN};
@@ -115,15 +115,15 @@ private:
SlewRate<float> _adjusted_yaw_rate_setpoint{0.f};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RO_MAX_THR_SPEED>) _param_ro_max_thr_speed,
(ParamFloat<px4::params::SV_MAX_THR_SPEED>) _param_sv_max_thr_speed,
(ParamFloat<px4::params::RA_WHEEL_BASE>) _param_ra_wheel_base,
(ParamFloat<px4::params::RA_MAX_STR_ANG>) _param_ra_max_str_ang,
(ParamFloat<px4::params::RO_YAW_RATE_LIM>) _param_ro_yaw_rate_limit,
(ParamFloat<px4::params::RO_YAW_RATE_TH>) _param_ro_yaw_rate_th,
(ParamFloat<px4::params::RO_YAW_RATE_P>) _param_ro_yaw_rate_p,
(ParamFloat<px4::params::RO_YAW_RATE_I>) _param_ro_yaw_rate_i,
(ParamFloat<px4::params::RO_YAW_ACCEL_LIM>) _param_ro_yaw_accel_limit,
(ParamFloat<px4::params::RO_SPEED_TH>) _param_ro_speed_th,
(ParamFloat<px4::params::RO_YAW_RATE_CORR>) _param_ro_yaw_rate_corr
(ParamFloat<px4::params::SV_YAW_RATE_LIM>) _param_sv_yaw_rate_limit,
(ParamFloat<px4::params::SV_YAW_RATE_TH>) _param_sv_yaw_rate_th,
(ParamFloat<px4::params::SV_YAW_RATE_P>) _param_sv_yaw_rate_p,
(ParamFloat<px4::params::SV_YAW_RATE_I>) _param_sv_yaw_rate_i,
(ParamFloat<px4::params::SV_YAW_ACCEL_LIM>) _param_sv_yaw_accel_limit,
(ParamFloat<px4::params::SV_SPEED_TH>) _param_sv_speed_th,
(ParamFloat<px4::params::SV_YAW_RATE_CORR>) _param_sv_yaw_rate_corr
)
};

Some files were not shown because too many files have changed in this diff Show More