Compare commits

..

1 Commits

Author SHA1 Message Date
Daniel Agar 9766fcfb6f [WIP] logger priority boost command line 2023-02-10 19:26:14 -05:00
315 changed files with 6218 additions and 10671 deletions
-2
View File
@@ -110,8 +110,6 @@ pipeline {
"raspberrypi_pico_default",
"sky-drones_smartap-airlink_default",
"spracing_h7extreme_default",
"thepeach_k1_default",
"thepeach_r1_default",
"uvify_core_default"
],
image: docker_images.nuttx,
-1
View File
@@ -30,7 +30,6 @@ jobs:
cuav_nora,
cuav_x7pro,
cubepilot_cubeorange,
cubepilot_cubeorangeplus,
cubepilot_cubeyellow,
diatone_mamba-f405-mk2,
freefly_can-rtk-gps,
+5 -5
View File
@@ -170,7 +170,7 @@
]
},
{
"label": "gazebo",
"label": "ign gazebo",
"type": "shell",
"options": {
"cwd": "${workspaceFolder}",
@@ -178,7 +178,7 @@
"IGN_GAZEBO_RESOURCE_PATH": "${workspaceFolder}/Tools/simulation/gz/models",
}
},
"command": "gz sim -v 4 -r ${workspaceFolder}/Tools/simulation/gz/worlds/${input:gzWorld}.sdf",
"command": "ign gazebo -v 4 -r ${workspaceFolder}/Tools/simulation/gz/worlds/${input:gzWorld}.sdf",
"isBackground": true,
"presentation": {
"echo": true,
@@ -191,7 +191,7 @@
"close": false
},
"problemMatcher": [],
"dependsOn":["gazebo kill"]
"dependsOn":["ign gazebo kill"]
},
{
"label": "gazebo-classic kill",
@@ -211,9 +211,9 @@
"dependsOn":["px4_sitl_cleanup"]
},
{
"label": "gazebo kill",
"label": "ign gazebo kill",
"type": "shell",
"command": "pkill -9 -f 'gz sim' || true",
"command": "pkill -9 -f 'ign gazebo' || true",
"presentation": {
"echo": true,
"reveal": "never",
+64 -71
View File
@@ -44,88 +44,81 @@ The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/con
## Maintenance Team
Note: This is the source of truth for the active maintainers of PX4 ecosystem.
* Project: Founder
* [Lorenz Meier](https://github.com/LorenzMeier)
* Architecture
* [Daniel Agar](https://github.com/dagar)
* [Dev Call](https://github.com/PX4/PX4-Autopilot/labels/devcall)
* [Ramon Roche](https://github.com/mrpollo)
* Communication Architecture
* [Beat Kueng](https://github.com/bkueng)
* [Julian Oes](https://github.com/JulianOes)
* UI in QGroundControl
* [Gus Grubba](https://github.com/dogmaphobic)
* [Multicopter Flight Control](https://github.com/PX4/PX4-Autopilot/labels/multicopter)
* [Mathieu Bresciani](https://github.com/bresch)
* [Multicopter Software Architecture](https://github.com/PX4/PX4-Autopilot/labels/multicopter)
* [Matthias Grob](https://github.com/MaEtUgR)
* [VTOL Flight Control](https://github.com/PX4/PX4-Autopilot/labels/vtol)
* [Roman Bapst](https://github.com/RomanBapst)
* [Fixed Wing Flight Control](https://github.com/PX4/PX4-Autopilot/labels/fixedwing)
* [Roman Bapst](https://github.com/RomanBapst)
* OS / NuttX
* [David Sidrane](https://github.com/davids5)
* Driver Architecture
* [Daniel Agar](https://github.com/dagar)
* Commander Architecture
* [Julian Oes](https://github.com/julianoes)
* [UAVCAN](https://github.com/PX4/PX4-Autopilot/labels/uavcan)
* [Daniel Agar](https://github.com/dagar)
* [State Estimation](https://github.com/PX4/PX4-Autopilot/issues?q=is%3Aopen+is%3Aissue+label%3A%22state+estimation%22)
* [Paul Riseborough](https://github.com/priseborough)
* Vision based navigation and Obstacle Avoidance
* [Markus Achtelik](https://github.com/markusachtelik)
* DDS/ROS2 Interface
* [Nuno Marques](https://github.com/TSC21)
| Sector | Maintainer |
|---|---|
| Founder | [Lorenz Meier](https://github.com/LorenzMeier) |
| Architecture | [Daniel Agar](https://github.com/dagar) / [Beat Küng](https://github.com/bkueng)|
| State Estimation | [Mathieu Bresciani](https://github.com/bresch) / [Paul Riseborough](https://github.com/priseborough) |
| OS/NuttX | [David Sidrane](https://github.com/davids5) |
| Drivers | [Daniel Agar](https://github.com/dagar) |
| Simulation | [Jaeyoung Lim](https://github.com/Jaeyoung-Lim) |
| ROS2 | [Beniamino Pozzan](https://github.com/beniaminopozzan) |
| Community QnA Call | [Ramon Roche](https://github.com/mrpollo) |
| [Documentation](https://docs.px4.io/main/en/) | [Hamish Willee](https://github.com/hamishwillee) |
| Vehicle Type | Maintainer |
|---|---|
| Multirotor | [Matthias Grob](https://github.com/MaEtUgR) |
| Fixed Wing | [Thomas Stastny](https://github.com/tstastny) |
| Hybrid VTOL | [Silvan Fuhrer](https://github.com/sfuhrer) |
| Boat | x |
| Rover | x |
See also [maintainers list](https://px4.io/community/maintainers/) (px4.io) and the [contributors list](https://github.com/PX4/PX4-Autopilot/graphs/contributors) (Github). However it may be not up to date.
See also [maintainers list](https://px4.io/community/maintainers/) (px4.io) and the [contributors list](https://github.com/PX4/PX4-Autopilot/graphs/contributors) (Github).
## Supported Hardware
Pixhawk standard boards and proprietary boards are shown below (discontinued boards aren't listed).
For the most up to date information, please visit [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
This repository contains code supporting Pixhawk standard boards (best supported, best tested, recommended choice) and proprietary boards.
### Pixhawk Standard Boards
* FMUv6X and FMUv6U (STM32H7, 2021)
* Various vendors will provide FMUv6X and FMUv6U based designs Q3/2021
* FMUv5 and FMUv5X (STM32F7, 2019/20)
* [Pixhawk 4 (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4.html)
* [Pixhawk 4 mini (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4_mini.html)
* [CUAV V5+ (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_plus.html)
* [CUAV V5 nano (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_nano.html)
* [Auterion Skynode (FMUv5X)](https://docs.auterion.com/skynode)
* FMUv4 (STM32F4, 2015)
* [Pixracer](https://docs.px4.io/main/en/flight_controller/pixracer.html)
* [Pixhawk 3 Pro](https://docs.px4.io/main/en/flight_controller/pixhawk3_pro.html)
* FMUv3 (STM32F4, 2014)
* [Pixhawk 2](https://docs.px4.io/main/en/flight_controller/pixhawk-2.html)
* [Pixhawk Mini](https://docs.px4.io/main/en/flight_controller/pixhawk_mini.html)
* [CUAV Pixhack v3](https://docs.px4.io/main/en/flight_controller/pixhack_v3.html)
* FMUv2 (STM32F4, 2013)
* [Pixhawk](https://docs.px4.io/main/en/flight_controller/pixhawk.html)
* [Pixfalcon](https://docs.px4.io/main/en/flight_controller/pixfalcon.html)
These boards fully comply with Pixhawk Standard, and are maintained by the PX4-Autopilot maintainers and Dronecode team
### Manufacturer and Community supported
* [Holybro Durandal](https://docs.px4.io/main/en/flight_controller/durandal.html)
* [Hex Cube Orange](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_orange.html)
* [Hex Cube Yellow](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_yellow.html)
* [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf)
* [Airmind MindRacer V1.2](http://mindpx.net/assets/accessories/mindracer_user_guide_v1.2.pdf)
* [Bitcraze Crazyflie 2.0](https://docs.px4.io/main/en/complete_vehicles/crazyflie2.html)
* [Omnibus F4 SD](https://docs.px4.io/main/en/flight_controller/omnibus_f4_sd.html)
* [Holybro Kakute F7](https://docs.px4.io/main/en/flight_controller/kakutef7.html)
* [Raspberry PI with Navio 2](https://docs.px4.io/main/en/flight_controller/raspberry_pi_navio2.html)
* FMUv6X and FMUv6C
* [CUAV Pixahwk V6X (FMUv6X)](https://docs.px4.io/main/en/flight_controller/cuav_pixhawk_v6x.html)
* [Holybro Pixhawk 6X (FMUv6X)](https://docs.px4.io/main/en/flight_controller/pixhawk6x.html)
* [Holybro Pixhawk 6C (FMUv6C)](https://docs.px4.io/main/en/flight_controller/pixhawk6c.html)
* [Holybro Pix32 v6 (FMUv6C)](https://docs.px4.io/main/en/flight_controller/holybro_pix32_v6.html)
* FMUv5 and FMUv5X (STM32F7, 2019/20)
* [Pixhawk 4 (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4.html)
* [Pixhawk 4 mini (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4_mini.html)
* [CUAV V5+ (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_plus.html)
* [CUAV V5 nano (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_nano.html)
* [Auterion Skynode (FMUv5X)](https://docs.auterion.com/avionics/skynode)
* FMUv4 (STM32F4, 2015)
* [Pixracer](https://docs.px4.io/main/en/flight_controller/pixracer.html)
* [Pixhawk 3 Pro](https://docs.px4.io/main/en/flight_controller/pixhawk3_pro.html)
* FMUv3 (STM32F4, 2014)
* [Pixhawk 2](https://docs.px4.io/main/en/flight_controller/pixhawk-2.html)
* [Pixhawk Mini](https://docs.px4.io/main/en/flight_controller/pixhawk_mini.html)
* [CUAV Pixhack v3](https://docs.px4.io/main/en/flight_controller/pixhack_v3.html)
* FMUv2 (STM32F4, 2013)
* [Pixhawk](https://docs.px4.io/main/en/flight_controller/pixhawk.html)
### Manufacturer supported
These boards are maintained to be compatible with PX4-Autopilot by the Manufacturers.
* [ARK Electronics ARKV6X](https://docs.px4.io/main/en/flight_controller/arkv6x.html)
* [Hex Cube Orange](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_orange.html)
* [Hex Cube Yellow](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_yellow.html)
* [Holybro Durandal](https://docs.px4.io/main/en/flight_controller/durandal.html)
* [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf)
* [Airmind MindRacer V1.2](http://mindpx.net/assets/accessories/mindracer_user_guide_v1.2.pdf)
* [Holybro Kakute F7](https://docs.px4.io/main/en/flight_controller/kakutef7.html)
### Community supported
These boards don't fully comply industry standards, and thus is solely maintained by the PX4 publc community members.
### Experimental
These boards are nor maintained by PX4 team nor Manufacturer, and is not guaranteed to be compatible with up to date PX4 releases.
* [Raspberry PI with Navio 2](https://docs.px4.io/main/en/flight_controller/raspberry_pi_navio2.html)
* [Bitcraze Crazyflie 2.0](https://docs.px4.io/main/en/complete_vehicles/crazyflie2.html)
Additional information about supported hardware can be found in [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
## Project Roadmap
**Note: Outdated**
A high level project roadmap is available [here](https://github.com/orgs/PX4/projects/25).
## Project Governance
@@ -12,10 +12,6 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadx}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
# disable some checks to allow to fly:
# - with usb
param set-default CBRK_USB_CHK 197848
@@ -11,11 +11,6 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=airplane}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# disable some checks to allow to fly:
# - with usb
param set-default CBRK_USB_CHK 197848
@@ -11,10 +11,6 @@
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=xvert}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 0
param set-default VT_FW_DIFTHR_EN 1
@@ -5,12 +5,12 @@
# @type Quadrotor Wide
#
. ${R}etc/init.d-posix/airframes/10016_gazebo-classic_iris
. ${R}etc/init.d-posix/airframes/10016_iris
# EKF2: Vision position and heading, no GPS
# EKF2: Vision position and heading
param set-default EKF2_AID_MASK 24
param set-default EKF2_EV_DELAY 5
param set-default EKF2_EV_CTRL 15
param set-default EKF2_HGT_REF 3
param set-default EKF2_GPS_CTRL 0
# LPE: Vision + baro
@@ -13,10 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
@@ -13,10 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_depth}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
@@ -10,11 +10,6 @@ PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0
@@ -60,6 +55,7 @@ param set-default RWTO_TKOFF 1
param set-default CA_AIRFRAME 1
param set-default COM_PREARM_MODE 2
param set-default CBRK_AIRSPD_CHK 162128
param set-default CA_ROTOR_COUNT 1
param set-default CA_ROTOR0_PX 0.3
@@ -1,109 +0,0 @@
#!/bin/sh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
. ${R}etc/init.d/rc.vtol_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
param set-default FD_ACT_EN 0
param set-default FD_ACT_MOT_TOUT 500
param set-default CA_AIRFRAME 2
param set-default COM_PREARM_MODE 2
param set-default CA_ROTOR_COUNT 5
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_ROTOR4_PX 0.2
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_MIN1 10
param set-default SIM_GZ_EC_MAX1 1500
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_MIN2 10
param set-default SIM_GZ_EC_MAX2 1500
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_MIN3 10
param set-default SIM_GZ_EC_MAX3 1500
param set-default SIM_GZ_EC_FUNC4 104
param set-default SIM_GZ_EC_MIN4 10
param set-default SIM_GZ_EC_MAX4 1500
param set-default SIM_GZ_EC_FUNC5 105
param set-default SIM_GZ_EC_MIN5 0
param set-default SIM_GZ_EC_MAX5 3500
param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_FUNC2 202
param set-default SIM_GZ_SV_FUNC3 203
param set-default COM_RC_IN_MODE 1
param set-default ASPD_PRIMARY 1
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default FW_L1_PERIOD 12
param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_TRIM 0.25
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2
param set-default MC_AIRMODE 1
param set-default MC_ROLLRATE_P 0.3
param set-default MC_YAW_P 1.6
param set-default MIS_TAKEOFF_ALT 10
param set-default MPC_ACC_HOR_MAX 2
param set-default MPC_XY_P 0.8
param set-default MPC_XY_VEL_P_ACC 3
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_D_ACC 0.1
param set-default NAV_ACC_RAD 5
param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 0.75
param set-default VT_B_TRANS_DUR 8
param set-default VT_TYPE 2
param set-default FD_ESCS_EN 0
@@ -1,12 +0,0 @@
#!/bin/sh
#
# @name Gazebo x500 vision
#
# @type Quadrotor
#
. ${R}etc/init.d-posix/airframes/4001_gz_x500
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_vision}
@@ -1,6 +1,8 @@
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
# shellcheck disable=SC2154
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_gcs_port_local
# shellcheck disable=SC2154
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u $udp_offboard_port_local
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_offboard_port_local
@@ -73,8 +73,6 @@ px4_add_romfs_files(
4001_gz_x500
4002_gz_x500_depth
4003_gz_rc_cessna
4004_gz_standard_vtol
4005_gz_x500_vision
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
@@ -8,28 +8,11 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
echo "INFO [init] SIH simulator"
if [ -n "${PX4_HOME_LAT}" ]; then
param set SIH_LOC_LAT0 ${PX4_HOME_LAT}
fi
if [ -n "${PX4_HOME_LON}" ]; then
param set SIH_LOC_LON0 ${PX4_HOME_LON}
fi
if simulator_sih start; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
else
echo "ERROR [init] simulator_sih failed to start"
@@ -94,22 +77,9 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
# start gz bridge with pose arg.
if gz_bridge start -p "${model_pose}" -m "${PX4_GZ_MODEL}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
fi
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
else
echo "ERROR [init] gz_bridge failed to start"
@@ -120,22 +90,9 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
# model name specificed, gz_bridge will attach to existing model
if gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
fi
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
else
echo "ERROR [init] gz_bridge failed to start"
@@ -147,22 +104,9 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
echo "WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL."
if gz_bridge start -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
fi
sensor_baro_sim start
sensor_gps_sim start
sensor_mag_sim start
else
echo "ERROR [init] gz_bridge failed to start"
@@ -36,7 +36,6 @@ add_subdirectory(airframes)
px4_add_romfs_files(
rc.airship_apps
rc.airship_defaults
rc.autostart_ext
rc.balloon_apps
rc.balloon_defaults
rc.boat_defaults
@@ -122,12 +122,16 @@ param set-default VT_TRANS_MIN_TM 15
param set-default VT_B_TRANS_DUR 8
param set-default VT_FWD_THRUST_SC 4
param set-default VT_F_TRANS_DUR 1
param set-default VT_B_REV_OUT 0.5
param set-default VT_B_TRANS_THR 0.7
param set-default VT_TRANS_TIMEOUT 22
param set-default VT_F_TRANS_RAMP 4
param set-default COM_RC_OVERRIDE 0
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 5
@@ -54,6 +54,14 @@ param set-default CBRK_AIRSPD_CHK 162128
# Differential drive acts like ackermann steering with a maximum turn angle of 180 degrees, or pi radians
param set-default GND_MAX_ANG 3.1415
param set-default RBCLW_BAUD 8
param set-default RBCLW_COUNTS_REV 1200
param set-default RBCLW_ADDRESS 128
# 104 corresponds to Telem 4
param set-default RBCLW_SER_CFG 104
# Start this driver after setting parameters, because the driver uses some of those parameters.
# roboclaw start /dev/ttyS3
# Set geometry & output configration
param set-default CA_AIRFRAME 6
param set-default CA_R_REV 3
@@ -17,6 +17,7 @@ param set-default COM_POS_FS_DELAY 5
# there is a 2.5 factor applied on the _FS thresholds if for invalidation
param set-default COM_POS_FS_EPH 50
param set-default COM_POS_FS_EPV 30
param set-default COM_VEL_FS_EVH 5
param set-default COM_POS_LOW_EPH 50
+1 -1
View File
@@ -25,7 +25,7 @@ if __name__ == "__main__":
if not os.path.isdir(output_dir):
os.mkdir(output_dir)
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../msg")
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"..")
msg_files = get_msgs_list(msg_path)
msg_files.sort()
+1 -2
View File
@@ -164,8 +164,7 @@ for field_type, field_name, field_size, padding in fields:
print('\tmemcpy(&topic.{0}, buf.iterator, sizeof(topic.{0}));'.format(field_name))
if field_type == 'uint64' and (field_name == 'timestamp' or field_name == 'timestamp_sample'):
print('\tif (topic.{0} == 0) topic.{0} = hrt_absolute_time();'.format(field_name, field_name))
print('\telse topic.{0} = math::min(topic.{0} - time_offset, hrt_absolute_time());'.format(field_name, field_name))
print('\ttopic.{0} -= time_offset;'.format(field_name))
print('\tbuf.iterator += sizeof(topic.{:});'.format(field_name))
print('\tbuf.offset += sizeof(topic.{:});'.format(field_name))
+1 -18
View File
@@ -102,7 +102,7 @@ class ModuleDocumentation(object):
def _handle_usage_param_int(self, args):
assert(len(args) == 6) # option_char, default_val, min_val, max_val, description, is_optional
option_char = self._get_option_char(args[0])
default_val = self._get_int(args[1])
default_val = int(args[1], 0)
description = self._get_string(args[4])
if self._is_bool_true(args[5]):
self._usage_string += " [-%s <val>] %s\n" % (option_char, description)
@@ -214,9 +214,6 @@ class ModuleDocumentation(object):
f = f[:-1]
return float(f)
def _get_int(self, argument):
return int(eval(argument))
def _is_string(self, argument):
return len(argument) > 0 and argument[0] == '"'
@@ -310,8 +307,6 @@ class SourceParser(object):
r'//.*?$|/\*.*?\*/|\'(?:\\.|[^\\\'])*\'|"(?:\\.|[^\\"])*"',
re.DOTALL | re.MULTILINE)
self._define_pattern = re.compile(r'#define\s+(\w+?)[^\S\r\n]+(.+?)\s*?\n')
def Parse(self, scope, contents):
"""
Incrementally parse program contents and append all found documentations
@@ -321,9 +316,6 @@ class SourceParser(object):
# remove comments from source
contents = self._comment_remover(contents)
# replace preprocessor defines defined in file directly
contents = self._define_replacer(contents)
extracted_function_calls = [] # list of tuples: (FUNC_NAME, list(ARGS))
start_index = 0
@@ -387,15 +379,6 @@ class SourceParser(object):
return s
return re.sub(self._comment_remove_pattern, replacer, text)
def _define_replacer(self, text):
""" check for C preprocesor #define in text and replace with argument"""
text = re.sub(r"\\\s*?\n"," ",text)
define_iter = self._define_pattern.finditer(text)
for define_pattern in define_iter:
text = re.sub(r"\b" +re.escape(str(define_pattern.groups()[0])) + r"\b", re.escape(str(define_pattern.groups()[1])), text)
return text
def _do_consistency_check(self, contents, scope, module_doc):
"""
check the documentation for consistency with the code (arguments to
+20 -23
View File
@@ -84,7 +84,6 @@ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends i
gdb \
git \
lcov \
libfuse2 \
libxml2-dev \
libxml2-utils \
make \
@@ -183,7 +182,6 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
echo "${NUTTX_GCC_VERSION} path already set.";
else
echo $exportline >> $HOME/.profile;
source $HOME/.profile; # Allows to directly build NuttX targets in the same terminal
fi
fi
fi
@@ -219,34 +217,33 @@ if [[ $INSTALL_SIM == "true" ]]; then
# Set Java 11 as default
sudo update-alternatives --set java $(update-alternatives --list java | grep "java-$java_version")
# Gazebo / Gazebo classic installation
# Install Gazebo
if [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
echo "Gazebo (Garden) will be installed"
echo "Earlier versions will be removed"
# Add Gazebo binary repository
sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
sudo apt-get update -y --quiet
# Install Gazebo
gazebo_packages="gz-garden"
else
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
# Update list, since new gazebo-stable.list has been added
sudo apt-get update -y --quiet
# Install Gazebo classic
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
gazebo_classic_version=9
gazebo_packages="gazebo$gazebo_classic_version libgazebo$gazebo_classic_version-dev"
else
# default and Ubuntu 20.04
gazebo_classic_version=11
gazebo_packages="gazebo$gazebo_classic_version libgazebo$gazebo_classic_version-dev"
fi
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
ignition-fortress \
;
fi
# Install Gazebo classic
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
gazebo_version=9
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
gazebo_packages="gazebo libgazebo-dev"
else
# default and Ubuntu 20.04
gazebo_version=11
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
fi
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
# Update list, since new gazebo-stable.list has been added
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
dmidecode \
$gazebo_packages \
+5 -13
View File
@@ -84,18 +84,6 @@
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
</link>
<link name="airspeed">
<pose>0 0 0 0 0 0</pose>
@@ -209,6 +197,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="left_elevon">
@@ -637,6 +626,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name="RightWheelJoint" type="revolute">
@@ -653,6 +643,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name="CenterWheelJoint" type="revolute">
@@ -669,6 +660,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
@@ -803,7 +795,7 @@
<sub_topic>servo_3</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@@ -1,15 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Standard VTOL</name>
<version>1.0</version>
<sdf version='1.10'>model.sdf</sdf>
<author>
<name>Roman Bapst</name>
<email>roman@px4.io</email>
</author>
<description>
This is a model of a standard VTOL quad plane.
</description>
</model>
@@ -1,755 +0,0 @@
<?xml version="1.0"?>
<!-- DO NOT EDIT: Generated from standard_vtol.sdf.jinja -->
<sdf version='1.10'>
<model name='standard_vtol'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>5</mass>
<inertia>
<ixx>0.477708333333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.341666666667</iyy>
<iyz>0</iyz>
<izz>0.811041666667</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 -0.07 0 0 0</pose>
<geometry>
<box>
<size>0.55 2.144 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1.0</kd>
<max_vel>0.1</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_visual'>
<pose>0.53 -1.072 -0.1 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_wing.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='left_motor_column'>
<pose>0 0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='right_motor_column'>
<pose>0 -0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m0'>
<pose>-0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m1'>
<pose>-0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m2'>
<pose>0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m3'>
<pose>0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
</link>
<link name='rotor_0'>
<pose>0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_1'>
<pose>-0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_2'>
<pose>0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_3'>
<pose>-0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_puller'>
<pose>-0.22 0 0.0 0 1.57 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<pose>0.0 0 -0.04 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_puller_visual'>
<pose>0 0 -0.04 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8 0.8 0.8</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<pose>0.0 0 0.0 0 -1.57 0</pose>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_elevon_visual'>
<pose>-0.105 0.004 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_left.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.6 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_elevon_visual'>
<pose>0.281 -1.032 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_right.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="elevator">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose> -0.5 0 0 0.00 0 0.0</pose>
</inertial>
</link>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.18 0.6 -0.005 0 0 0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.18 -0.6 -0.005 0 0 -0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 -0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>-0.2</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0</cp>
<area>0.01</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>3500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.01</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>4</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<static>0</static>
</model>
</sdf>
+5 -13
View File
@@ -215,18 +215,6 @@
</friction>
</surface>
</collision>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
@@ -302,6 +290,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_1">
@@ -374,6 +363,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_2">
@@ -446,6 +436,7 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_3">
@@ -518,9 +509,10 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
@@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500-vision</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Jaeyoung Lim</name>
<email>jalim@ethz.ch</email>
</author>
<description>Model of the X500 with a odometry/external vision input.</description>
</model>
@@ -1,13 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-vision'>
<include merge='true'>
<uri>x500</uri>
</include>
<plugin
filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
<dimensions>3</dimensions>
</plugin>
</model>
</sdf>
+12 -13
View File
@@ -5,22 +5,21 @@
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
<plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
<plugin name='ignition::gazebo::systems::Imu' filename='ignition-gazebo-imu-system'/>
<plugin name='ignition::gazebo::systems::Sensors' filename='ignition-gazebo-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>
<plugin name='3D View' filename='GzScene3D'>
<gz-gui>
<ignition-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</gz-gui>
</ignition-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
@@ -28,7 +27,7 @@
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<plugin name='World control' filename='WorldControl'>
<gz-gui>
<ignition-gui>
<title>World control</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
@@ -40,13 +39,13 @@
<line own='left' target='left'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
</ignition-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name='World stats' filename='WorldStats'>
<gz-gui>
<ignition-gui>
<title>World stats</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
@@ -58,7 +57,7 @@
<line own='right' target='right'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
</ignition-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
@@ -379,7 +379,7 @@
#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */
#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */
// GPIO_UART5_RTS No remap /* PC8 */
// GPIO_UART5_RTS no remap /* PC8 */
// GPIO_UART5_CTS No remap /* PC9 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
@@ -387,8 +387,8 @@
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
#define GPIO_UART7_RTS (GPIO_UART7_RTS_2 | GPIO_PULLDOWN) /* PF8 */
#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */
#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */
#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
@@ -65,13 +65,16 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
@@ -82,6 +85,8 @@ CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
+1 -1
View File
@@ -3,9 +3,9 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
@@ -19,7 +19,6 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
@@ -50,6 +49,7 @@ CONFIG_MODULES_FW_PATH_NAVIGATION=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
@@ -65,13 +65,16 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
@@ -82,6 +85,8 @@ CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
@@ -4,27 +4,12 @@
#------------------------------------------------------------------------------
board_adc start
# Variants
# 1. Isolated {ICM42688p, ICM20948(with mag)}, body-fixed {ICM20649}
# 2. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM20649, ICM45686, AK09918}
# 3. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM45686, AK09918}
# SPI4 is isolated, SPI1 is body-fixed
# SPI4, isolated
# SPI4
ms5611 -s -b 4 start
icm42688p -s -b 4 -R 10 start
icm20948 -s -b 4 -R 10 -M start
icm42688p -s -b 4 -R 10 start -c 15
if ! icm20948 -s -b 4 -R 10 -M -q start
then
icm42688p -s -b 4 -R 6 start -c 13
fi
# SPI1, body-fixed
if ! icm45686 -s -b 1 -R 3 -q start
then
icm20649 -s -b 1 start
fi
# SPI1
ms5611 -s -b 1 start
icm20649 -s -b 1 start
@@ -7,49 +7,21 @@
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CMP is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorangeplus/nuttx-config"
@@ -58,7 +30,7 @@ CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H747XI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
@@ -68,11 +40,11 @@ CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=79954
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1058
@@ -84,11 +56,11 @@ CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
@@ -112,10 +84,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=2944
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
@@ -134,6 +103,9 @@ CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -155,16 +127,17 @@ CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
@@ -257,4 +230,6 @@ CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
@@ -44,16 +44,6 @@
#include <stdint.h>
#include <stm32_gpio.h>
/**
* If NuttX is built without support for SMPS it can brick the hardware.
* Therefore, we make sure the NuttX headers are correct.
*/
#include "hardware/stm32h7x3xx_pwr.h"
#if STM32_PWR_CR3_SMPSEXTHP != (1 << 3)
# error "No SMPS support in NuttX submodule");
#endif
/* PX4IO connection configuration */
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS3"
@@ -38,7 +38,6 @@
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}), // MPU_CS, MPU_DRDY
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortG, GPIO::Pin1}), // ICM45686_CS
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}), // BARO_CS
}),
@@ -49,7 +48,6 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin4}), // MPU_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin15}), // ACCEL_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin13}), // GYRO_EXT_CS
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}), // BARO_EXT_CS
}),
};
@@ -22,10 +22,13 @@ param set-default CBRK_SUPPLY_CHK 894281
# Select the Generic 250 Racer by default
param set-default SYS_AUTOSTART 4050
# use EKF2 without mag
# use the Q attitude estimator, it works w/o mag or GPS.
param set-default SYS_MC_EST_GROUP 3
param set-default ATT_ACC_COMP 0
param set-default ATT_W_ACC 0.4000
param set-default ATT_W_GYRO_BIAS 0.0000
param set-default SYS_HAS_MAG 0
# and enable gravity fusion
param set-default EKF2_IMU_CONTROL 7
# the startup tune is not great on a binary output buzzer, so disable it
param set-default CBRK_BUZZER 782090
@@ -38,5 +41,11 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Store missions in RAM
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
@@ -138,8 +138,6 @@
#define GPIO_RF_SWITCH /* PE13 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN13)
#define GPIO_VTX_ON /* PB11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
/* Power switch controls ******************************************************/
#define SDIO_SLOTNO 0 /* Only one slot */
@@ -181,7 +179,6 @@
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN, \
GPIO_RF_SWITCH, \
GPIO_VTX_ON, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
@@ -22,10 +22,13 @@ param set-default CBRK_SUPPLY_CHK 894281
# Select the Generic 250 Racer by default
param set-default SYS_AUTOSTART 4050
# use EKF2 without mag
# use the Q attitude estimator, it works w/o mag or GPS.
param set-default SYS_MC_EST_GROUP 3
param set-default ATT_ACC_COMP 0
param set-default ATT_W_ACC 0.4000
param set-default ATT_W_GYRO_BIAS 0.0000
param set-default SYS_HAS_MAG 0
# and enable gravity fusion
param set-default EKF2_IMU_CONTROL 7
# the startup tune is not great on a binary output buzzer, so disable it
param set-default CBRK_BUZZER 782090
@@ -135,8 +135,6 @@
#define GPIO_RF_SWITCH /* PE13 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN13)
#define GPIO_VTX_ON /* PB11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
/* Power switch controls ******************************************************/
#define SDIO_SLOTNO 0 /* Only one slot */
@@ -180,7 +178,6 @@
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN, \
GPIO_RF_SWITCH, \
GPIO_VTX_ON, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
@@ -12,7 +12,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MUORB_SLPI=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_ORB_COMMUNICATOR=y
@@ -31,6 +31,7 @@ CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -50,6 +51,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -96,3 +98,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
+3
View File
@@ -32,6 +32,7 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -51,6 +52,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -97,3 +99,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
+2
View File
@@ -31,6 +31,7 @@ CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -50,6 +51,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
-2
View File
@@ -195,7 +195,5 @@ __EXPORT int board_app_initialize(uintptr_t arg)
sdio_mediachange(sdio_dev, true);
#endif /* CONFIG_MMCSD */
px4_platform_configure();
return OK;
}
-1
View File
@@ -2,7 +2,6 @@ CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_TESTING=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
-2
View File
@@ -4,8 +4,6 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_COMMON_LIGHT=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
@@ -15,7 +15,6 @@ param set-default MAV_1_REMOTE_PRT 14550
param set-default MAV_1_UDP_PRT 14550
param set-default SENS_EXT_I2C_PRB 0
param set-default CYPHAL_ENABLE 0
if param greater -s UAVCAN_ENABLE 0
then
@@ -23,11 +22,4 @@ then
ifup can1
ifup can2
ifup can3
fi
if param greater -s CYPHAL_ENABLE 0
then
ifup can0
ifup can1
ifup can2
ifup can3
fi
fi
+1 -3
View File
@@ -29,14 +29,12 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
# CONFIG_SENSORS_VEHICLE_OPTICAL_FLOW is not set
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MFT=y
-1
View File
@@ -3,7 +3,6 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
-1
View File
@@ -4,4 +4,3 @@ CONFIG_DRIVERS_UAVCAN=n
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_ESC_CONTROLLER=y
+1 -8
View File
@@ -47,7 +47,6 @@ then
fi
fi
if ver hwtypecmp V6X000004 V6X001004 V6X004004 V6X005004
then
# Internal SPI bus ICM20649
@@ -102,13 +101,7 @@ if ver hwtypecmp V6X002001
then
rm3100 -I -b 4 start
else
if ver hwtypecmp V6X009010 V6X010010
then
# Internal magnetometer on I2C
bmm150 -I -R 0 start
else
bmm150 -I -R 6 start
fi
bmm150 -I -R 6 start
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)
@@ -35,6 +35,7 @@ CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -54,6 +55,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -99,3 +101,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
+5
View File
@@ -5,8 +5,13 @@ uint8 INDEX_ROLL = 0
uint8 INDEX_PITCH = 1
uint8 INDEX_YAW = 2
uint8 INDEX_THROTTLE = 3
uint8 INDEX_FLAPS = 4
uint8 INDEX_SPOILERS = 5
uint8 INDEX_AIRBRAKES = 6
uint8 INDEX_LANDING_GEAR = 7
uint8 INDEX_GIMBAL_SHUTTER = 3
uint8 INDEX_CAMERA_ZOOM = 4
uint8 INDEX_COLLECTIVE_TILT = 8
uint8 GROUP_INDEX_ATTITUDE = 0
uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1
+1 -1
View File
@@ -5,4 +5,4 @@ uint32 noutputs # valid outputs
float32[16] output # output data, in natural output units
# actuator_outputs_sim is used for SITL, HITL & SIH (with an output range of [-1, 1])
# TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug
# TOPICS actuator_outputs actuator_outputs_sim
+1 -2
View File
@@ -128,7 +128,6 @@ set(msg_files
MountOrientation.msg
ModeCompleted.msg
NavigatorMissionItem.msg
NormalizedUnsignedSetpoint.msg
NpfgStatus.msg
ObstacleDistance.msg
OffboardControlMode.msg
@@ -179,7 +178,6 @@ set(msg_files
TaskStackInfo.msg
TecsStatus.msg
TelemetryStatus.msg
TiltrotorExtraControls.msg
TimesyncStatus.msg
TrajectoryBezier.msg
TrajectorySetpoint.msg
@@ -220,6 +218,7 @@ set(msg_files
VehicleTrajectoryBezier.msg
VehicleTrajectoryWaypoint.msg
VtolVehicleStatus.msg
WheelEncoders.msg
Wind.msg
YawEstimatorStatus.msg
)
-2
View File
@@ -5,14 +5,12 @@ float32 esc_voltage # Voltage measured from current ESC [V] - if supported
float32 esc_current # Current measured from current ESC [A] - if supported
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported
uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
uint8 esc_cmdcount # Counter of number of commands
uint8 esc_state # State of ESC - depend on Vendor
uint8 actuator_function # actuator output function (one of Motor1...MotorN)
uint16 failures # Bitmask to indicate the internal ESC faults
int8 esc_power # Applied power 0-100 in % (negative values reserved)
uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0)
uint8 FAILURE_OVER_VOLTAGE = 1 # (1 << 1)
+1 -1
View File
@@ -17,7 +17,6 @@ uint32 mode_req_offboard_signal
uint32 mode_req_home_position
uint32 mode_req_wind_and_flight_time_compliance # if set, mode cannot be entered if wind or flight time limit exceeded
uint32 mode_req_prevent_arming # if set, cannot arm while in this mode
uint32 mode_req_manual_control
uint32 mode_req_other # other requirements, not covered above (for external modes)
@@ -29,6 +28,7 @@ bool local_position_invalid # Local position estimate invalid
bool local_position_invalid_relaxed # Local position with reduced accuracy requirements invalid (e.g. flying with optical flow)
bool local_velocity_invalid # Local velocity estimate invalid
bool global_position_invalid # Global position estimate invalid
bool gps_position_invalid # GPS position invalid
bool auto_mission_missing # No mission available
bool offboard_control_signal_lost # Offboard signal lost
bool home_position_invalid # No home position available
+1 -1
View File
@@ -26,7 +26,7 @@ float32 pitch # move forward, negative pitch rotation, nose down
float32 yaw # positive yaw rotation, clockwise when seen top down
float32 throttle # move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust
float32 flaps # position of flaps switch/knob/lever [-1, 1]
float32 flaps # flap position
float32 aux1
float32 aux2
-5
View File
@@ -1,5 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 normalized_setpoint # [0, 1]
# TOPICS flaps_setpoint spoilers_setpoint
+5
View File
@@ -28,3 +28,8 @@ float32 throttle_trim # estimated throttle value [0,1] required to fly level a
uint8 mode
uint8 TECS_MODE_NORMAL = 0
uint8 TECS_MODE_UNDERSPEED = 1
uint8 TECS_MODE_TAKEOFF = 2
uint8 TECS_MODE_LAND = 3
uint8 TECS_MODE_LAND_THROTTLELIM = 4
uint8 TECS_MODE_BAD_DESCENT = 5
uint8 TECS_MODE_CLIMBOUT = 6
-4
View File
@@ -1,4 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 collective_tilt_normalized_setpoint # Collective tilt angle of motors of tiltrotor, 0: vertical, 1: horizontal [0, 1]
float32 collective_thrust_normalized_setpoint # Collective thrust setpoint [0, 1]
+10
View File
@@ -17,4 +17,14 @@ bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change)
bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway)
uint8 apply_flaps # flap config specifier
uint8 FLAPS_OFF = 0 # no flaps
uint8 FLAPS_LAND = 1 # landing config flaps
uint8 FLAPS_TAKEOFF = 2 # take-off config flaps
uint8 apply_spoilers # spoiler config specifier
uint8 SPOILERS_OFF = 0 # no spoilers
uint8 SPOILERS_LAND = 1 # landing config spoiler
uint8 SPOILERS_DESCEND = 2 # descend config spoiler
# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint
+5
View File
@@ -0,0 +1,5 @@
uint64 timestamp # time since system start (microseconds)
int64 encoder_position # The wheel position, in encoder counts since boot. Positive is forward rotation, negative is reverse rotation
int32 speed # Speed of each wheel, in encoder counts per second. Positive is forward, negative is reverse
uint32 pulses_per_rev # Number of pulses per revolution for each wheel
@@ -99,10 +99,7 @@ __END_DECLS
#define PX4_ROOTFSDIR CONFIG_BOARD_ROOTFSDIR
// Qurt doesn't have an SD card for storage
#ifndef __PX4_QURT
#define PX4_STORAGEDIR PX4_ROOTFSDIR
#endif
/****************************************************************************
* Defines for POSIX and ROS
@@ -76,18 +76,18 @@ static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -18};
static constexpr wq_config_t uavcan{"wq:uavcan", 3624, -19};
static constexpr wq_config_t ttyS0{"wq:ttyS0", 1728, -21};
static constexpr wq_config_t ttyS1{"wq:ttyS1", 1728, -22};
static constexpr wq_config_t ttyS2{"wq:ttyS2", 1728, -23};
static constexpr wq_config_t ttyS3{"wq:ttyS3", 1728, -24};
static constexpr wq_config_t ttyS4{"wq:ttyS4", 1728, -25};
static constexpr wq_config_t ttyS5{"wq:ttyS5", 1728, -26};
static constexpr wq_config_t ttyS6{"wq:ttyS6", 1728, -27};
static constexpr wq_config_t ttyS7{"wq:ttyS7", 1728, -28};
static constexpr wq_config_t ttyS8{"wq:ttyS8", 1728, -29};
static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30};
static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31};
static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32};
static constexpr wq_config_t ttyS0{"wq:ttyS0", 1632, -21};
static constexpr wq_config_t ttyS1{"wq:ttyS1", 1632, -22};
static constexpr wq_config_t ttyS2{"wq:ttyS2", 1632, -23};
static constexpr wq_config_t ttyS3{"wq:ttyS3", 1632, -24};
static constexpr wq_config_t ttyS4{"wq:ttyS4", 1632, -25};
static constexpr wq_config_t ttyS5{"wq:ttyS5", 1632, -26};
static constexpr wq_config_t ttyS6{"wq:ttyS6", 1632, -27};
static constexpr wq_config_t ttyS7{"wq:ttyS7", 1632, -28};
static constexpr wq_config_t ttyS8{"wq:ttyS8", 1632, -29};
static constexpr wq_config_t ttyS9{"wq:ttyS9", 1632, -30};
static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1632, -31};
static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1632, -32};
static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50};
@@ -124,13 +124,6 @@ typedef struct {
// wait for the sensor hub if its data is coming from it.
#define SCHED_PRIORITY_ESTIMATOR (PX4_WQ_HP_BASE - 5)
// Logger watchdog priority, triggered when a task busy-loops (and
// restored after a short time).
// The priority is a trade-off between:
// - ability to capture any busy-looping task below this priority
// - not having a negative impact on the system itself
#define SCHED_PRIORITY_LOG_WATCHDOG (PX4_WQ_HP_BASE - 6)
// Position controllers typically are in a blocking wait on estimator data
// so when new sensor data is available they will run last. Keeping them
// on a high priority ensures that they are the first process to be run
@@ -148,8 +141,12 @@ typedef struct {
// The navigation system needs to execute regularly but has no realtime needs
#define SCHED_PRIORITY_NAVIGATION (SCHED_PRIORITY_DEFAULT + 5)
// SCHED_PRIORITY_DEFAULT
#define SCHED_PRIORITY_LOG_WRITER (SCHED_PRIORITY_DEFAULT - 10)
#define SCHED_PRIORITY_PARAMS (SCHED_PRIORITY_DEFAULT - 15)
#define SCHED_PRIORITY_LOG_WRITER (SCHED_PRIORITY_DEFAULT - 40)
// SCHED_PRIORITY_IDLE
typedef int (*px4_main_t)(int argc, char *argv[]);
+2 -2
View File
@@ -347,12 +347,12 @@ void orb_print_message_internal(const orb_metadata *meta, const void *data, bool
data_offset += sizeof(uint64_t);
} else if (strcmp(c_type, "float") == 0) {
if (!dont_print) { PX4_INFO_RAW("%.5f", (double) * (float *)(data_ptr + data_offset)); }
if (!dont_print) { PX4_INFO_RAW("%.4f", (double) * (float *)(data_ptr + data_offset)); }
data_offset += sizeof(float);
} else if (strcmp(c_type, "double") == 0) {
if (!dont_print) { PX4_INFO_RAW("%.6f", *(double *)(data_ptr + data_offset)); }
if (!dont_print) { PX4_INFO_RAW("%.4f", *(double *)(data_ptr + data_offset)); }
data_offset += sizeof(double);
@@ -40,6 +40,14 @@ __BEGIN_DECLS
#include <stm32.h>
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F4
#define PX4_FLASH_BASE STM32_FLASH_BASE
#if defined(CONFIG_STM32_STM32F4XXX)
# include <stm32_bbsram.h>
# define PX4_BBSRAM_SIZE STM32_BBSRAM_SIZE
# define PX4_HF_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL
# define HAS_BBSRAM CONFIG_STM32_BBSRAM
# define BBSRAM_FILE_COUNT CONFIG_STM32_BBSRAM_FILES
# define SAVE_CRASHDUMP CONFIG_STM32_SAVE_CRASHDUMP
#endif
#define PX4_NUMBER_I2C_BUSES STM32_NI2C
#define PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL 16
+2 -5
View File
@@ -14,11 +14,11 @@
"environment": [
{
"name": "PX4_SIM_MODEL",
"value": "gz_${input:PX4_GZ_MODEL}"
"value": "${input:PX4_GZ_MODEL}"
}
],
"externalConsole": false,
"postDebugTask": "gazebo kill",
"postDebugTask": "ign gazebo kill",
"linux": {
"MIMode": "gdb",
"externalConsole": false,
@@ -222,9 +222,6 @@
"description": "GZ vehicle model",
"options": [
"x500",
"x500_depth",
"rc_cessna",
"standard_vtol",
],
"default": "x500"
}
+31 -82
View File
@@ -105,8 +105,7 @@ static int create_dirs();
static int run_startup_script(const std::string &commands_file, const std::string &absolute_binary_path, int instance);
static std::string get_absolute_binary_path(const std::string &argv0);
static void wait_to_exit();
static int get_server_running(int instance, bool *is_running);
static int set_server_running(int instance);
static bool is_server_running(int instance, bool server);
static void print_usage();
static bool dir_exists(const std::string &path);
static bool file_exists(const std::string &name);
@@ -125,7 +124,6 @@ int main(int argc, char **argv)
{
bool is_client = false;
bool pxh_off = false;
bool server_is_running = false;
/* Symlinks point to all commands that can be used as a client with a prefix. */
const char prefix[] = PX4_SHELL_COMMAND_PREFIX;
@@ -133,9 +131,6 @@ int main(int argc, char **argv)
std::string absolute_binary_path; // full path to the px4 binary being executed
int ret = PX4_OK;
int instance = 0;
if (argc > 0) {
/* The executed binary name could start with a path, so strip it away */
const std::string full_binary_name = argv[0];
@@ -151,6 +146,8 @@ int main(int argc, char **argv)
}
if (is_client) {
int instance = 0;
if (argc >= 3 && strcmp(argv[1], "--instance") == 0) {
instance = strtoul(argv[2], nullptr, 10);
/* update argv so that "--instance <instance>" is not visible anymore */
@@ -163,16 +160,15 @@ int main(int argc, char **argv)
PX4_DEBUG("instance: %i", instance);
ret = get_server_running(instance, &server_is_running);
if (!is_server_running(instance, false)) {
if (errno) {
PX4_ERR("Failed to communicate with daemon: %s", strerror(errno));
if (ret != PX4_OK) {
PX4_ERR("PX4 client failed to get server status");
return ret;
}
} else {
PX4_ERR("PX4 daemon not running yet");
}
if (!server_is_running) {
PX4_ERR("PX4 server not running");
return PX4_ERROR;
return -1;
}
/* Remove the path and prefix. */
@@ -206,6 +202,7 @@ int main(int argc, char **argv)
bool working_directory_default = false;
int instance = 0;
bool instance_provided = false;
int myoptind = 1;
@@ -295,27 +292,20 @@ int main(int argc, char **argv)
PX4_INFO("working directory %s", working_directory.c_str());
}
ret = change_directory(working_directory);
int ret = change_directory(working_directory);
if (ret != PX4_OK) {
return ret;
}
}
ret = get_server_running(instance, &server_is_running);
if (ret != PX4_OK) {
PX4_ERR("Failed to get server status");
return ret;
}
if (server_is_running) {
if (is_server_running(instance, true)) {
// allow running multiple instances, but the server is only started for the first
PX4_INFO("PX4 server already running for instance %i", instance);
return PX4_ERROR;
PX4_INFO("PX4 daemon already running for instance %i (%s)", instance, strerror(errno));
return -1;
}
ret = create_symlinks_if_needed(data_path);
int ret = create_symlinks_if_needed(data_path);
if (ret != PX4_OK) {
return ret;
@@ -353,13 +343,6 @@ int main(int argc, char **argv)
px4::init_once();
px4::init(argc, argv, "px4");
// Don't set this up until PX4 is up and running
ret = set_server_running(instance);
if (ret != PX4_OK) {
return ret;
}
ret = run_startup_script(commands_file, absolute_binary_path, instance);
if (ret == 0) {
@@ -635,73 +618,39 @@ void print_usage()
printf(" e.g.: px4-commander status\n");
}
int get_server_running(int instance, bool *is_server_running)
bool is_server_running(int instance, bool server)
{
const std::string file_lock_path = std::string(LOCK_FILE_PATH) + '-' + std::to_string(instance);
int fd = open(file_lock_path.c_str(), O_RDWR | O_CREAT, 0666);
if (fd < 0) {
PX4_ERR("%s: failed to create lock file: %s, reason=%s", __func__, file_lock_path.c_str(), strerror(errno));
return PX4_ERROR;
PX4_ERR("is_server_running: failed to create lock file: %s, reason=%s", file_lock_path.c_str(), strerror(errno));
return false;
}
int status = PX4_OK;
struct flock lock;
memset(&lock, 0, sizeof(struct flock));
bool result = false;
// Exclusive write lock, cover the entire file (regardless of size)
lock.l_type = F_WRLCK;
lock.l_whence = SEEK_SET;
if (fcntl(fd, F_GETLK, &lock) < 0) {
PX4_ERR("%s: failed to get check for lock on file: %s, reason=%s", __func__, file_lock_path.c_str(), strerror(errno));
status = PX4_ERROR;
} else {
// F_GETLK will set l_type to F_UNLCK if no one had a lock on the file. Otherwise,
// it means that the server is running and has a lock on the file
if (lock.l_type != F_UNLCK) {
*is_server_running = true;
// Server is running if the file is already locked.
if (flock(fd, LOCK_EX | LOCK_NB) < 0) {
if (errno == EWOULDBLOCK) {
// a server is running!
result = true;
} else {
*is_server_running = false;
PX4_ERR("is_server_running: failed to get lock on file: %s, reason=%s", file_lock_path.c_str(), strerror(errno));
result = false;
}
}
close(fd);
return status;
}
int set_server_running(int instance)
{
const std::string file_lock_path = std::string(LOCK_FILE_PATH) + '-' + std::to_string(instance);
int fd = open(file_lock_path.c_str(), O_RDWR | O_CREAT, 0666);
if (fd < 0) {
PX4_ERR("%s: failed to create lock file: %s, reason=%s", __func__, file_lock_path.c_str(), strerror(errno));
return PX4_ERROR;
}
int status = PX4_OK;
struct flock lock;
memset(&lock, 0, sizeof(struct flock));
// Exclusive lock, cover the entire file (regardless of size).
lock.l_type = F_WRLCK;
lock.l_whence = SEEK_SET;
if (fcntl(fd, F_SETLK, &lock) < 0) {
PX4_ERR("%s: failed to set lock on file: %s, reason=%s", __func__, file_lock_path.c_str(), strerror(errno));
status = PX4_ERROR;
if (result || !server) {
close(fd);
}
// note: server leaks the file handle, on purpose, in order to keep the lock on the file until the process terminates.
// note: server leaks the file handle once, on purpose, in order to keep the lock on the file until the process terminates.
// In this case we return false so the server code path continues now that we have the lock.
return status;
errno = 0;
return result;
}
bool file_exists(const std::string &name)
+3 -4
View File
@@ -166,12 +166,11 @@ static px4_task_t px4_task_spawn_internal(const char *name, int priority, px4_ma
return -1;
} else {
strcpy(taskmap[task_index].argv_storage[i], argv[i]);
//px4_clock_gettimemap[task_index].argv_storage[i], argv[i]);
taskmap[task_index].argv[i] = taskmap[task_index].argv_storage[i];
}
} else {
// Must add NULL at end of argv
taskmap[task_index].argv[i] = nullptr;
break;
}
@@ -421,13 +420,13 @@ int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *ts)
return 0;
}
int px4_prctl(int option, const char *arg2, px4_task_t pid)
int px4_prctl(int option, const char *arg2, pthread_t pid)
{
int rv = -1;
pthread_mutex_lock(&task_mutex);
for (int i = 0; i < PX4_MAX_TASKS; i++) {
if (taskmap[i].isused && taskmap[i].tid == (pthread_t) pid) {
if (taskmap[i].isused && taskmap[i].tid == pid) {
rv = pthread_attr_setthreadname(&taskmap[i].attr, arg2);
return rv;
}
+87 -46
View File
@@ -65,13 +65,12 @@ ModalIo::ModalIo() :
_esc_status.esc[i].esc_address = 0;
_esc_status.esc[i].esc_rpm = 0;
_esc_status.esc[i].esc_state = 0;
_esc_status.esc[i].esc_cmdcount = 0;
//_esc_status.esc[i].esc_cmdcount = 0;
_esc_status.esc[i].esc_voltage = 0;
_esc_status.esc[i].esc_current = 0;
_esc_status.esc[i].esc_temperature = 0;
_esc_status.esc[i].esc_errorcount = 0;
_esc_status.esc[i].failures = 0;
_esc_status.esc[i].esc_power = 0;
}
qc_esc_packet_init(&_fb_packet);
@@ -153,8 +152,6 @@ int ModalIo::load_params(modal_io_params_t *params, ch_assign_t *map)
param_get(param_find("MODAL_IO_RPM_MIN"), &params->rpm_min);
param_get(param_find("MODAL_IO_RPM_MAX"), &params->rpm_max);
param_get(param_find("MODAL_IO_VLOG"), &params->verbose_logging);
if (params->rpm_min >= params->rpm_max) {
PX4_ERR("Invalid parameter MODAL_IO_RPM_MIN. Please verify parameters.");
params->rpm_min = 0;
@@ -339,9 +336,9 @@ int ModalIo::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
_esc_status.esc[id].esc_address = motor_idx + 1; //remapped motor ID
_esc_status.esc[id].timestamp = tnow;
_esc_status.esc[id].esc_rpm = fb.rpm;
_esc_status.esc[id].esc_power = fb.power;
//_esc_status.esc[id].esc_power = fb.power;
_esc_status.esc[id].esc_state = fb.id_state & 0x0F;
_esc_status.esc[id].esc_cmdcount = fb.cmd_counter;
//_esc_status.esc[id].esc_cmdcount = fb.cmd_counter;
_esc_status.esc[id].esc_voltage = _esc_chans[id].voltage;
_esc_status.esc[id].esc_current = _esc_chans[id].current;
_esc_status.esc[id].failures = 0; //not implemented
@@ -588,7 +585,7 @@ int ModalIo::custom_command(int argc, char *argv[])
}
if (!strcmp(verb, "reset")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
if (esc_id < 4) {
PX4_INFO("Reset ESC: %i", esc_id);
cmd.len = qc_esc_create_reset_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = false;
@@ -600,7 +597,7 @@ int ModalIo::custom_command(int argc, char *argv[])
}
} else if (!strcmp(verb, "version")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
if (esc_id < 4) {
PX4_INFO("Request version for ESC: %i", esc_id);
cmd.len = qc_esc_create_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = true;
@@ -613,7 +610,7 @@ int ModalIo::custom_command(int argc, char *argv[])
}
} else if (!strcmp(verb, "version-ext")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
if (esc_id < 4) {
PX4_INFO("Request extended version for ESC: %i", esc_id);
cmd.len = qc_esc_create_extended_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = true;
@@ -626,14 +623,14 @@ int ModalIo::custom_command(int argc, char *argv[])
}
} else if (!strcmp(verb, "tone")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
if (0 < esc_id && esc_id < 16) {
PX4_INFO("Request tone for ESC mask: %i", esc_id);
cmd.len = qc_esc_create_sound_packet(period, duration, power, esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = false;
return get_instance()->send_cmd_thread_safe(&cmd);
} else {
print_usage("Invalid ESC ID, use 0-3");
print_usage("Invalid ESC mask, use 1-15");
return 0;
}
@@ -655,20 +652,42 @@ int ModalIo::custom_command(int argc, char *argv[])
}
} else if (!strcmp(verb, "rpm")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
PX4_INFO("Request RPM for ESC ID: %i - RPM: %i", esc_id, rate);
int16_t rate_req[MODAL_IO_OUTPUT_CHANNELS] = {0, 0, 0, 0};
if (0 < esc_id && esc_id < 16) {
PX4_INFO("Request RPM for ESC bit mask: %i - RPM: %i", esc_id, rate);
int16_t rate_req[MODAL_IO_OUTPUT_CHANNELS];
int16_t outputs[MODAL_IO_OUTPUT_CHANNELS];
outputs[0] = (esc_id & 1) ? rate : 0;
outputs[1] = (esc_id & 2) ? rate : 0;
outputs[2] = (esc_id & 4) ? rate : 0;
outputs[3] = (esc_id & 8) ? rate : 0;
//the motor mapping is.. if I want to spin Motor 1 (1-4) then i need to provide non-zero rpm for motor map[m-1]
modal_io_params_t params;
ch_assign_t map[MODAL_IO_OUTPUT_CHANNELS];
get_instance()->load_params(&params, (ch_assign_t *)&map);
uint8_t id_fb_raw = 0;
uint8_t id_fb = 0;
if (esc_id == 0xFF) {
rate_req[0] = rate;
rate_req[1] = rate;
rate_req[2] = rate;
rate_req[3] = rate;
if (esc_id & 1) { id_fb_raw = 0; }
} else {
rate_req[esc_id] = rate;
id_fb = esc_id;
else if (esc_id & 2) { id_fb_raw = 1; }
else if (esc_id & 4) { id_fb_raw = 2; }
else if (esc_id & 8) { id_fb_raw = 3; }
for (int i = 0; i < MODAL_IO_OUTPUT_CHANNELS; i++) {
int motor_idx = map[i].number - 1; // user defined mapping is 1-4, array is 0-3
if (motor_idx >= 0 && motor_idx < MODAL_IO_OUTPUT_CHANNELS) {
rate_req[i] = outputs[motor_idx] * map[i].direction;
}
if (motor_idx == id_fb_raw) {
id_fb = i;
}
}
cmd.len = qc_esc_create_rpm_packet4_fb(rate_req[0],
@@ -689,31 +708,53 @@ int ModalIo::custom_command(int argc, char *argv[])
cmd.repeat_delay_us = repeat_delay_us;
cmd.print_feedback = true;
PX4_INFO("feedback id debug: %i", id_fb);
PX4_INFO("ESC map: %d %d %d %d", map[0].number, map[1].number, map[2].number, map[3].number);
PX4_INFO("feedback id debug: %i, %i", id_fb_raw, id_fb);
PX4_INFO("Sending UART ESC RPM command %i", rate);
return get_instance()->send_cmd_thread_safe(&cmd);
} else {
print_usage("Invalid ESC ID, use 0-3");
print_usage("Invalid ESC mask, use 1-15");
return 0;
}
} else if (!strcmp(verb, "pwm")) {
if (esc_id < MODAL_IO_OUTPUT_CHANNELS) {
PX4_INFO("Request PWM for ESC ID: %i - PWM: %i", esc_id, rate);
int16_t rate_req[MODAL_IO_OUTPUT_CHANNELS] = {0, 0, 0, 0};
if (0 < esc_id && esc_id < 16) {
PX4_INFO("Request PWM for ESC mask: %i - PWM: %i", esc_id, rate);
int16_t rate_req[MODAL_IO_OUTPUT_CHANNELS];
int16_t outputs[MODAL_IO_OUTPUT_CHANNELS];
outputs[0] = (esc_id & 1) ? rate : 0;
outputs[1] = (esc_id & 2) ? rate : 0;
outputs[2] = (esc_id & 4) ? rate : 0;
outputs[3] = (esc_id & 8) ? rate : 0;
modal_io_params_t params;
ch_assign_t map[MODAL_IO_OUTPUT_CHANNELS];
get_instance()->load_params(&params, (ch_assign_t *)&map);
uint8_t id_fb_raw = 0;
uint8_t id_fb = 0;
if (esc_id == 0xFF) {
rate_req[0] = rate;
rate_req[1] = rate;
rate_req[2] = rate;
rate_req[3] = rate;
if (esc_id & 1) { id_fb_raw = 0; }
} else {
rate_req[esc_id] = rate;
id_fb = esc_id;
else if (esc_id & 2) { id_fb_raw = 1; }
else if (esc_id & 4) { id_fb_raw = 2; }
else if (esc_id & 8) { id_fb_raw = 3; }
for (int i = 0; i < MODAL_IO_OUTPUT_CHANNELS; i++) {
int motor_idx = map[i].number - 1; // user defined mapping is 1-4, array is 0-3
if (motor_idx >= 0 && motor_idx < MODAL_IO_OUTPUT_CHANNELS) {
rate_req[i] = outputs[motor_idx] * map[i].direction;
PX4_INFO("rate_req[%d]=%d", i, rate_req[i]);
}
if (motor_idx == id_fb_raw) {
id_fb = i;
}
}
cmd.len = qc_esc_create_pwm_packet4_fb(rate_req[0],
@@ -734,9 +775,11 @@ int ModalIo::custom_command(int argc, char *argv[])
cmd.repeat_delay_us = repeat_delay_us;
cmd.print_feedback = true;
PX4_INFO("feedback id debug: %i", id_fb);
PX4_INFO("ESC map: %d %d %d %d", map[0].number, map[1].number, map[2].number, map[3].number);
PX4_INFO("feedback id debug: %i, %i", id_fb_raw, id_fb);
PX4_INFO("Sending UART ESC power command %i", rate);
return get_instance()->send_cmd_thread_safe(&cmd);
} else {
@@ -1114,7 +1157,8 @@ bool ModalIo::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
//check_for_esc_timeout();
// publish the actual command that we sent and the feedback received
if (_parameters.verbose_logging) {
/*
if (MODALAI_PUBLISH_ESC_STATUS) {
actuator_outputs_s actuator_outputs{};
actuator_outputs.noutputs = num_outputs;
@@ -1125,10 +1169,9 @@ bool ModalIo::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
actuator_outputs.timestamp = hrt_absolute_time();
_outputs_debug_pub.publish(actuator_outputs);
_esc_status_pub.publish(_esc_status);
}
_esc_status_pub.publish(_esc_status);
*/
perf_count(_output_update_perf);
@@ -1320,9 +1363,7 @@ void ModalIo::Run()
}
if (_current_cmd.response) {
if (read_response(&_current_cmd) == 0) {
_esc_status_pub.publish(_esc_status);
}
read_response(&_current_cmd);
}
} else {
@@ -1392,19 +1433,19 @@ $ todo
PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false);
PRINT_MODULE_USAGE_COMMAND_DESCR("rpm", "Closed-Loop RPM test control request");
PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false);
PRINT_MODULE_USAGE_PARAM_INT('i', 1, 1, 15, "ESC ID bitmask, 1-15", false);
PRINT_MODULE_USAGE_PARAM_INT('r', 0, -32768, 32768, "RPM, -32,768 to 32,768", false);
PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1<<31, "Command repeat count, 0 to INT_MAX", false);
PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1<<31, "Delay between repeated commands (microseconds), 0 to INT_MAX", false);
PRINT_MODULE_USAGE_COMMAND_DESCR("pwm", "Open-Loop PWM test control request");
PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false);
PRINT_MODULE_USAGE_PARAM_INT('i', 1, 1, 15, "ESC ID bitmask, 1-15", false);
PRINT_MODULE_USAGE_PARAM_INT('r', 0, 0, 800, "Duty Cycle value, 0 to 800", false);
PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1<<31, "Command repeat count, 0 to INT_MAX", false);
PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1<<31, "Delay between repeated commands (microseconds), 0 to INT_MAX", false);
PRINT_MODULE_USAGE_COMMAND_DESCR("tone", "Send tone generation request to ESC");
PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false);
PRINT_MODULE_USAGE_PARAM_INT('i', 1, 1, 15, "ESC ID bitmask, 1-15", false);
PRINT_MODULE_USAGE_PARAM_INT('p', 0, 0, 255, "Period of sound, inverse frequency, 0-255", false);
PRINT_MODULE_USAGE_PARAM_INT('d', 0, 0, 255, "Duration of the sound, 0-255, 1LSB = 13ms", false);
PRINT_MODULE_USAGE_PARAM_INT('v', 0, 0, 100, "Power (volume) of sound, 0-100", false);
+1 -2
View File
@@ -143,7 +143,6 @@ private:
int32_t function_map[MODAL_IO_OUTPUT_CHANNELS] {0, 0, 0, 0};
int32_t motor_map[MODAL_IO_OUTPUT_CHANNELS] {1, 2, 3, 4};
int32_t direction_map[MODAL_IO_OUTPUT_CHANNELS] {1, 1, 1, 1};
int32_t verbose_logging{0};
} modal_io_params_t;
struct EscChan {
@@ -189,7 +188,7 @@ private:
uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)};
uORB::Subscription _led_update_sub{ORB_ID(led_control)};
uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
//uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
modal_io_params_t _parameters;
@@ -201,16 +201,3 @@ PARAM_DEFINE_INT32(MODAL_IO_T_EXPO, 35);
* @increment 0.001
*/
PARAM_DEFINE_FLOAT(MODAL_IO_T_COSP, 0.990);
/**
* UART ESC verbose logging
*
* @reboot_required true
*
* @group MODAL IO
* @value 0 - Disabled
* @value 1 - Enabled
* @min 0
* @max 1
*/
PARAM_DEFINE_INT32(MODAL_IO_VLOG, 0);
+48 -68
View File
@@ -53,7 +53,6 @@
#include <lib/perf/perf_counter.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/actuator_test.h>
#include <uORB/topics/esc_status.h>
#include <drivers/drv_hrt.h>
#include <lib/mixer_module/mixer_module.hpp>
@@ -70,30 +69,61 @@ public:
static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS;
UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) :
UavcanPublisher(handle, pmgr, "udral.", "esc") { };
UavcanPublisher(handle, pmgr, "udral", "esc") { };
~UavcanEscController() {};
void update() override
{
actuator_test_s actuator_test;
if (_actuator_test_sub.update(&actuator_test)) {
_actuator_test_timestamp = actuator_test.timestamp;
}
if (_armed_sub.updated()) {
actuator_armed_s new_arming;
_armed_sub.update(&new_arming);
if (new_arming.armed != _armed.armed) {
_armed = new_arming;
publish_readiness();
}
}
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
if (hrt_absolute_time() > _previous_pub_time + READINESS_PUBLISH_PERIOD) {
publish_readiness();
// Only publish if we have a valid publication ID set
if (_port_id == 0) {
return;
}
reg_udral_service_common_Readiness_0_1 msg_arming {};
if (_armed.armed) {
msg_arming.value = reg_udral_service_common_Readiness_0_1_ENGAGED;
} else if (_armed.prearmed) {
msg_arming.value = reg_udral_service_common_Readiness_0_1_STANDBY;
} else {
msg_arming.value = reg_udral_service_common_Readiness_0_1_SLEEP;
}
uint8_t arming_payload_buffer[reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
CanardPortID arming_pid = static_cast<CanardPortID>(static_cast<uint32_t>(_port_id) + 1);
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = arming_pid, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _arming_transfer_id,
};
int result = reg_udral_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_arming_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&arming_payload_buffer
);
}
}
}
};
@@ -101,7 +131,7 @@ public:
{
if (_port_id > 0) {
reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0};
size_t payload_size = reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
for (uint8_t i = 0; i < MAX_ACTUATORS; i++) {
if (i < num_outputs) {
@@ -113,6 +143,10 @@ public:
}
}
PX4_INFO("Publish %d values %f, %f, %f, %f", num_outputs, (double)msg_sp.value[0], (double)msg_sp.value[1],
(double)msg_sp.value[2], (double)msg_sp.value[3]);
uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
const CanardTransferMetadata transfer_metadata = {
@@ -148,64 +182,10 @@ private:
*/
void esc_status_sub_cb(const CanardRxTransfer &msg);
void publish_readiness()
{
const hrt_abstime now = hrt_absolute_time();
_previous_pub_time = now;
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
// Only publish if we have a valid publication ID set
if (_port_id == 0) {
return;
}
reg_udral_service_common_Readiness_0_1 msg_arming {};
if (_armed.armed || _actuator_test_timestamp + 100_ms > now) {
msg_arming.value = reg_udral_service_common_Readiness_0_1_ENGAGED;
} else if (_armed.prearmed) {
msg_arming.value = reg_udral_service_common_Readiness_0_1_STANDBY;
} else {
msg_arming.value = reg_udral_service_common_Readiness_0_1_SLEEP;
}
uint8_t arming_payload_buffer[reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
CanardPortID arming_pid = static_cast<CanardPortID>(static_cast<uint32_t>(_port_id) + 1);
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = arming_pid, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _arming_transfer_id,
};
int result = reg_udral_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_arming_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&arming_payload_buffer);
}
};
uint8_t _rotor_count {0};
static constexpr hrt_abstime READINESS_PUBLISH_PERIOD = 100000;
hrt_abstime _previous_pub_time = 0;
uORB::Subscription _armed_sub{ORB_ID(actuator_armed)};
actuator_armed_s _armed {};
uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)};
uint64_t _actuator_test_timestamp{0};
CanardTransferID _arming_transfer_id;
};
+2 -2
View File
@@ -131,7 +131,7 @@ void CanardHandle::receive()
} else if (result == 1) {
// A transfer has been received, process it.
// PX4_INFO("received Port ID: %d", receive.metadata.port_id);
// PX4_INFO("received Port ID: %d", receive.port_id);
if (subscription != nullptr) {
UavcanBaseSubscriber *sub_instance = (UavcanBaseSubscriber *)subscription->user_reference;
@@ -145,7 +145,7 @@ void CanardHandle::receive()
_canard_instance.memory_free(&_canard_instance, (void *)receive.payload);
} else {
// PX4_INFO("RX canard %li\n", result);
//PX4_INFO("RX canard %d", result);
}
}
+3 -12
View File
@@ -83,8 +83,6 @@ CyphalNode::CyphalNode(uint32_t node_id, size_t capacity, size_t mtu_bytes) :
_pub_manager.updateParams();
_sub_manager.subscribe();
_mixing_output.mixingOutput().setMaxTopicUpdateRate(1000000 / 200);
}
CyphalNode::~CyphalNode()
@@ -137,7 +135,6 @@ int CyphalNode::start(uint32_t node_id, uint32_t bitrate)
_instance->active_bitrate = bitrate;
_instance->ScheduleOnInterval(ScheduleIntervalMs * 1000);
_instance->_mixing_output.ScheduleNow();
return PX4_OK;
}
@@ -257,19 +254,17 @@ void CyphalNode::print_info()
_pub_manager.printInfo();
PX4_INFO("Message subscriptions:");
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindMessage),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
PX4_INFO("Message port id %d", sub->port_id);
} else {
((UavcanBaseSubscriber *)sub->user_reference)->printInfo(sub->port_id);
((UavcanBaseSubscriber *)sub->user_reference)->printInfo();
}
});
PX4_INFO("Service response subscriptions:");
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindRequest),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
@@ -280,7 +275,6 @@ void CyphalNode::print_info()
}
});
PX4_INFO("Service request subscriptions:");
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindResponse),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
@@ -399,11 +393,8 @@ bool UavcanMixingInterface::updateOutputs(bool stop_motors, uint16_t outputs[MAX
// Hence, the mutex lock in UavcanMixingInterface::Run() is in effect
/// TODO: Need esc/servo metadata / bitmask(s)
auto publisher = static_cast<UavcanEscController *>(_pub_manager.getPublisher("esc"));
if (publisher) {
publisher->update_outputs(stop_motors, outputs, num_outputs);
}
_esc_controller.update_outputs(stop_motors, outputs, num_outputs);
// _servo_controller.update_outputs(stop_motors, outputs, num_outputs);
return true;
}
+10 -5
View File
@@ -82,10 +82,11 @@ class UavcanMixingInterface : public OutputModuleInterface
{
public:
UavcanMixingInterface(pthread_mutex_t &node_mutex,
PublicationManager &pub_manager)
UavcanEscController &esc_controller) //, UavcanServoController &servo_controller)
: OutputModuleInterface(MODULE_NAME "-actuators", px4::wq_configurations::uavcan),
_node_mutex(node_mutex),
_pub_manager(pub_manager) {}
_esc_controller(esc_controller)/*,
_servo_controller(servo_controller)*/ {}
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
@@ -102,7 +103,8 @@ protected:
private:
friend class CyphalNode;
pthread_mutex_t &_node_mutex;
PublicationManager &_pub_manager;
UavcanEscController &_esc_controller;
// UavcanServoController &_servo_controller;
MixingOutput _mixing_output{"UCAN1_ESC", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
};
@@ -113,7 +115,7 @@ class CyphalNode : public ModuleParams, public px4::ScheduledWorkItem
* Base interval, has to be complemented with events from the CAN driver
* and uORB topics sending data, to decrease response time.
*/
static constexpr unsigned ScheduleIntervalMs = 3;
static constexpr unsigned ScheduleIntervalMs = 10;
public:
@@ -176,6 +178,9 @@ private:
PublicationManager _pub_manager {_canard_handle, _param_manager};
SubscriptionManager _sub_manager {_canard_handle, _param_manager};
UavcanMixingInterface _mixing_output {_node_mutex, _pub_manager};
/// TODO: Integrate with PublicationManager
UavcanEscController _esc_controller {_canard_handle, _param_manager};
UavcanMixingInterface _mixing_output {_node_mutex, _esc_controller};
};
+13 -13
View File
@@ -117,19 +117,19 @@ private:
const UavcanParamBinder _uavcan_params[13] {
{"uavcan.pub.udral.esc.0.id", "UCAN1_ESC_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.udral.servo.0.id", "UCAN1_SERVO_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.udral.gps.0.id", "UCAN1_GPS_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.udral.actuator_outputs.0.id", "UCAN1_ACTR_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.esc.0.id", "UCAN1_ESC0_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.gps.0.id", "UCAN1_GPS0_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.gps.1.id", "UCAN1_GPS1_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.energy_source.0.id", "UCAN1_BMS_ES_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.battery_status.0.id", "UCAN1_BMS_BS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.battery_parameters.0.id", "UCAN1_BMS_BP_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.udral.legacy_bms.0.id", "UCAN1_LG_BMS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS_P", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.esc.0.id", "UCAN1_ESC_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.servo.0.id", "UCAN1_SERVO_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.gps.0.id", "UCAN1_GPS_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.actuator_outputs.0.id", "UCAN1_ACTR_PUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.esc.0.id", "UCAN1_ESC0_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.gps.0.id", "UCAN1_GPS0_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.gps.1.id", "UCAN1_GPS1_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.energy_source.0.id", "UCAN1_BMS_ES_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.battery_status.0.id", "UCAN1_BMS_BS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.battery_parameters.0.id", "UCAN1_BMS_BP_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.legacy_bms.0.id", "UCAN1_LG_BMS_SUB", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.sub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
{"uavcan.pub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS_P", px4_param_to_uavcan_port_id, uavcan_port_id_to_px4_param},
//{"uavcan.sub.bms.0.id", "UCAN1_BMS0_SUB"}, //FIXME instancing
//{"uavcan.sub.bms.1.id", "UCAN1_BMS1_SUB"},
};
-12
View File
@@ -114,18 +114,6 @@ void PublicationManager::updateParams()
updateDynamicPublications();
}
UavcanPublisher *PublicationManager::getPublisher(const char *subject_name)
{
for (auto &dynpub : _dynpublishers) {
if (strcmp(dynpub->getSubjectName(), subject_name) == 0) {
return dynpub;
}
}
return NULL;
}
void PublicationManager::update()
{
for (auto &dynpub : _dynpublishers) {
+3 -5
View File
@@ -101,8 +101,6 @@ public:
void printInfo();
void updateParams();
UavcanPublisher *getPublisher(const char *subject_name);
private:
void updateDynamicPublications();
@@ -118,7 +116,7 @@ private:
{
return new UavcanGnssPublisher(handle, pmgr, 0);
},
"udral.gps",
"gps",
0
},
#endif
@@ -128,7 +126,7 @@ private:
{
return new UavcanEscController(handle, pmgr);
},
"udral.esc",
"esc",
0
},
#endif
@@ -138,7 +136,7 @@ private:
{
return new UavcanReadinessPublisher(handle, pmgr, 0);
},
"udral.readiness",
"readiness",
0
},
#endif
@@ -122,26 +122,18 @@ public:
return _subj_sub._subject_name;
}
const char *getSubjectPrefix()
{
return _prefix_name;
}
uint8_t getInstance()
{
return _instance;
}
void printInfo(CanardPortID port_id = CANARD_PORT_ID_UNSET)
void printInfo()
{
SubjectSubscription *curSubj = &_subj_sub;
while (curSubj != nullptr) {
if (curSubj->_canard_sub.port_id != CANARD_PORT_ID_UNSET) {
if (port_id == CANARD_PORT_ID_UNSET ||
port_id == curSubj->_canard_sub.port_id) {
PX4_INFO("Subscribed %s.%d on port %d", curSubj->_subject_name, _instance, curSubj->_canard_sub.port_id);
}
PX4_INFO("Subscribed %s.%d on port %d", curSubj->_subject_name, _instance, curSubj->_canard_sub.port_id);
}
curSubj = curSubj->next;
@@ -61,8 +61,6 @@ public:
void updateParam()
{
SubjectSubscription *curSubj = &_subj_sub;
bool unsubscribeRequired = false;
bool subscribeRequired = false;
while (curSubj != nullptr) {
char uavcan_param[90];
@@ -78,37 +76,29 @@ public:
if (curSubj->_canard_sub.port_id != new_id) {
if (new_id == CANARD_PORT_ID_UNSET) {
// Cancel subscription
unsubscribeRequired = true;
unsubscribe();
} else {
if (curSubj->_canard_sub.port_id != CANARD_PORT_ID_UNSET) {
// Already active; unsubscribe first
unsubscribeRequired = true;
unsubscribe();
}
// Subscribe on the new port ID
curSubj->_canard_sub.port_id = (CanardPortID)new_id;
PX4_INFO("Subscribing %s%s.%d on port %d", _prefix_name, curSubj->_subject_name, _instance,
curSubj->_canard_sub.port_id);
subscribeRequired = true;
subscribe();
}
}
} else if (curSubj->_canard_sub.port_id != CANARD_PORT_ID_UNSET) { // No valid sub id unsubscribe when neccesary
// Already active; unsubscribe first
unsubscribeRequired = true;
unsubscribe();
}
curSubj = curSubj->next;
}
if (unsubscribeRequired) {
unsubscribe();
}
if (subscribeRequired) {
subscribe();
}
};
UavcanDynamicPortSubscriber *next()
@@ -110,7 +110,7 @@ public:
bat_status.connected = true; // Based on some threshold or an error??
// Estimate discharged mah from Joule
if (PX4_ISFINITE(_nominal_voltage)) {
if (_nominal_voltage != NAN) {
bat_status.discharged_mah = (source_ts.value.full_energy.joule - source_ts.value.energy.joule)
/ (_nominal_voltage * WH_TO_JOULE);
}
+1 -4
View File
@@ -78,13 +78,10 @@ void SubscriptionManager::updateDynamicSubscriptions()
while (dynsub != nullptr) {
// Check if subscriber has already been created
const char *subj_prefix = dynsub->getSubjectPrefix();
const char *subj_name = dynsub->getSubjectName();
const uint8_t instance = dynsub->getInstance();
char subject_name[90];
snprintf(subject_name, sizeof(subject_name), "%s%s", subj_prefix, subj_name);
if (strcmp(subject_name, sub.subject_name) == 0 && instance == sub.instance) {
if (strcmp(subj_name, sub.subject_name) == 0 && instance == sub.instance) {
found_subscriber = true;
break;
}
+5 -5
View File
@@ -126,7 +126,7 @@ private:
{
return new UavcanEscSubscriber(handle, pmgr, 0);
},
"udral.esc",
"esc",
0
},
#endif
@@ -136,7 +136,7 @@ private:
{
return new UavcanGnssSubscriber(handle, pmgr, 0);
},
"udral.gps",
"gps",
0
},
#endif
@@ -146,7 +146,7 @@ private:
{
return new UavcanGnssSubscriber(handle, pmgr, 1);
},
"udral.gps",
"gps",
1
},
#endif
@@ -156,7 +156,7 @@ private:
{
return new UavcanBmsSubscriber(handle, pmgr, 0);
},
"udral.energy_source",
"energy_source",
0
},
#endif
@@ -166,7 +166,7 @@ private:
{
return new UavcanLegacyBatteryInfoSubscriber(handle, pmgr, 0);
},
"udral.legacy_bms",
"legacy_bms",
0
},
#endif
@@ -1,50 +0,0 @@
############################################################################
#
# Copyright (c) 2022-2023 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__distance_sensor__lightware_sf45_serial
MAIN lightware_sf45_serial
COMPILE_FLAGS
SRCS
lightware_sf45_serial.cpp
lightware_sf45_serial.hpp
lightware_sf45_serial_main.cpp
DEPENDS
drivers_rangefinder
px4_work_queue
MODULE_CONFIG
module.yaml
)
if(PX4_TESTING)
add_subdirectory(tests)
endif()
@@ -1,5 +0,0 @@
menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL
bool "lightware_sf45_serial"
default n
---help---
Enable support for lightware_sf45_serial
@@ -1,761 +0,0 @@
/**************************************************************************
*
* Copyright (c) 2022-2023 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 "lightware_sf45_serial.hpp"
#include "sf45_commands.h"
#include <inttypes.h>
#include <fcntl.h>
#include <termios.h>
#include <lib/systemlib/crc.h>
#include <float.h>
#include <mathlib/mathlib.h>
#include <matrix/matrix/math.hpp>
/* Configuration Constants */
#define SF45_MAX_PAYLOAD 256
#define SF45_SCALE_FACTOR 0.01f
SF45LaserSerial::SF45LaserSerial(const char *port, uint8_t rotation) :
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
_px4_rangefinder(0, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err"))
{
/* store port name */
strncpy(_port, port, sizeof(_port) - 1);
/* enforce null termination */
_port[sizeof(_port) - 1] = '\0';
device::Device::DeviceId device_id;
device_id.devid_s.bus_type = device::Device::DeviceBusType_SERIAL;
uint8_t bus_num = atoi(&_port[strlen(_port) - 1]); // Assuming '/dev/ttySx'
if (bus_num < 10) {
device_id.devid_s.bus = bus_num;
}
_num_retries = 2;
_px4_rangefinder.set_device_id(device_id.devid);
_px4_rangefinder.set_device_type(DRV_DIST_DEVTYPE_LIGHTWARE_LASER);
// populate obstacle map members
_obstacle_map_msg.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD;
_obstacle_map_msg.increment = 5;
_obstacle_map_msg.angle_offset = -2.5;
_obstacle_map_msg.min_distance = UINT16_MAX;
_obstacle_map_msg.max_distance = 5000;
}
SF45LaserSerial::~SF45LaserSerial()
{
stop();
perf_free(_sample_perf);
perf_free(_comms_errors);
}
int SF45LaserSerial::init()
{
param_get(param_find("SF45_UPDATE_CFG"), &_update_rate);
param_get(param_find("SF45_ORIENT_CFG"), &_orient_cfg);
param_get(param_find("SF45_YAW_CFG"), &_yaw_cfg);
/* SF45/B (50M) */
_px4_rangefinder.set_min_distance(0.2f);
_px4_rangefinder.set_max_distance(50.0f);
_interval = 10000;
start();
return PX4_OK;
}
int SF45LaserSerial::measure()
{
int rate = (int)_update_rate;
_data_output = 0x101; // raw distance + yaw readings
_stream_data = 5; // enable constant streaming
// send some packets so the sensor starts scanning
switch (_sensor_state) {
// sensor should now respond
case 0:
while (_num_retries--) {
sf45_send(SF_PRODUCT_NAME, false, &_product_name[0], 0);
_sensor_state = 0;
}
_sensor_state = 1;
break;
case 1:
// Update rate default to 50 readings/s
sf45_send(SF_UPDATE_RATE, true, &rate, sizeof(uint8_t));
_sensor_state = 2;
break;
case 2:
sf45_send(SF_DISTANCE_OUTPUT, true, &_data_output, sizeof(_data_output));
_sensor_state = 3;
break;
case 3:
sf45_send(SF_STREAM, true, &_stream_data, sizeof(_stream_data));
_sensor_state = 4;
break;
default:
break;
}
return PX4_OK;
}
int SF45LaserSerial::collect()
{
perf_begin(_sample_perf);
/* clear buffer if last read was too long ago */
int64_t read_elapsed = hrt_elapsed_time(&_last_read);
int ret;
/* the buffer for read chars is buflen minus null termination */
param_get(param_find("SF45_CP_LIMIT"), &_collision_constraint);
uint8_t readbuf[SF45_MAX_PAYLOAD];
float distance_m = -1.0f;
/* read from the sensor (uart buffer) */
const hrt_abstime timestamp_sample = hrt_absolute_time();
if (_sensor_state == 1) {
ret = ::read(_fd, &readbuf[0], 22);
sf45_request_handle(ret, readbuf);
ScheduleDelayed(_interval * 2);
} else if (_sensor_state == 2) {
ret = ::read(_fd, &readbuf[0], 7);
if (readbuf[3] == SF_UPDATE_RATE) {
sf45_request_handle(ret, readbuf);
ScheduleDelayed(_interval * 5);
}
} else if (_sensor_state == 3) {
ret = ::read(_fd, &readbuf[0], 8);
if (readbuf[3] == SF_DISTANCE_OUTPUT) {
sf45_request_handle(ret, readbuf);
ScheduleDelayed(_interval * 5);
}
} else {
ret = ::read(_fd, &readbuf[0], 10);
uint8_t flags_payload = (readbuf[1] >> 6) | (readbuf[2] << 2);
if (readbuf[3] == SF_DISTANCE_DATA_CM && flags_payload == 5) {
for (uint8_t i = 0; i < ret; ++i) {
sf45_request_handle(ret, readbuf);
}
if (_init_complete) {
sf45_process_replies(&distance_m);
} // end if
} else {
ret = ::read(_fd, &readbuf[0], 10);
}
}
if (ret < 0) {
PX4_DEBUG("read err: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
/* only throw an error if we time out */
if (read_elapsed > (_interval * 2)) {
PX4_DEBUG("Timing out...");
return ret;
} else {
return -EAGAIN;
}
} else if (ret == 0) {
return -EAGAIN;
}
_last_read = hrt_absolute_time();
if (!_crc_valid) {
return -EAGAIN;
}
PX4_DEBUG("val (float): %8.4f, raw: %s, valid: %s", (double)distance_m, _linebuf, ((_crc_valid) ? "OK" : "NO"));
_px4_rangefinder.update(timestamp_sample, distance_m);
perf_end(_sample_perf);
return PX4_OK;
}
void SF45LaserSerial::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
/* schedule a cycle to start things */
ScheduleNow();
}
void SF45LaserSerial::stop()
{
ScheduleClear();
}
void SF45LaserSerial::Run()
{
/* fds initialized? */
if (_fd < 0) {
/* open fd: non-blocking read mode*/
_fd = ::open(_port, O_RDWR | O_NOCTTY);
if (_fd < 0) {
PX4_ERR("open failed (%i)", errno);
return;
}
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
tcgetattr(_fd, &uart_config);
uart_config.c_cflag = (uart_config.c_cflag & ~CSIZE) | CS8;
uart_config.c_cflag |= (CLOCAL | CREAD);
// no parity, 1 stop bit, flow control disabled
uart_config.c_cflag &= ~(PARENB | PARODD);
uart_config.c_cflag |= 0;
uart_config.c_cflag &= ~CSTOPB;
uart_config.c_cflag &= ~CRTSCTS;
uart_config.c_iflag &= ~IGNBRK;
uart_config.c_iflag &= ~ICRNL;
uart_config.c_iflag &= ~(IXON | IXOFF | IXANY);
// echo and echo NL off, canonical mode off (raw mode)
// extended input processing off, signal chars off
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
uart_config.c_oflag = 0;
uart_config.c_cc[VMIN] = 0;
uart_config.c_cc[VTIME] = 1;
unsigned speed = B921600;
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
PX4_ERR("CFG: %d ISPD", termios_state);
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
PX4_ERR("CFG: %d OSPD", termios_state);
}
if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
PX4_ERR("baud %d ATTR", termios_state);
}
}
if (_collect_phase) {
/* perform collection */
int collect_ret = collect();
if (collect_ret == -EAGAIN) {
/* reschedule to grab the missing bits, time to transmit 8 bytes @ 9600 bps */
ScheduleDelayed(1042 * 8);
return;
}
if (OK != collect_ret) {
/* we know the sensor needs about four seconds to initialize */
if (hrt_absolute_time() > 5 * 1000 * 1000LL && _consecutive_fail_count < 5) {
PX4_ERR("collection error #%u", _consecutive_fail_count);
}
_consecutive_fail_count++;
/* restart the measurement state machine */
start();
return;
} else {
/* apparently success */
_consecutive_fail_count = 0;
}
/* next phase is measurement */
_collect_phase = false;
}
/* measurement phase */
if (OK != measure()) {
PX4_DEBUG("measure error");
}
/* next phase is collection */
_collect_phase = true;
/* schedule a fresh cycle call when the measurement is done */
ScheduleDelayed(_interval);
}
void SF45LaserSerial::print_info()
{
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
}
void SF45LaserSerial::sf45_request_handle(int return_val, uint8_t *input_buf)
{
// SF45 protocol
// Start byte is 0xAA and is the start of packet
// Payload length sanity check (0-1023) bytes
// and represented by 16-bit integer (payload +
// read/write status)
// ID byte precedes the data in the payload
// CRC comprised of 16-bit checksum (not included in checksum calc.)
uint16_t recv_crc = 0;
bool restart_flag = false;
while (restart_flag != true) {
switch (_parsed_state) {
case 0: {
if (input_buf[0] == 0xAA) {
// start of frame is valid, continue
_sop_valid = true;
_calc_crc = sf45_format_crc(_calc_crc, _start_of_frame);
_parsed_state = 1;
break;
} else {
_sop_valid = false;
_crc_valid = false;
_parsed_state = 0;
restart_flag = true;
_calc_crc = 0;
PX4_INFO("INFO: start of packet not valid");
break;
} // end else
} // end case 0
case 1: {
rx_field.flags_lo = input_buf[1];
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_lo);
_parsed_state = 2;
break;
}
case 2: {
rx_field.flags_hi = input_buf[2];
rx_field.data_len = (rx_field.flags_hi << 2) | (rx_field.flags_lo >> 6);
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_hi);
// Check payload length against known max value
if (rx_field.data_len > 17) {
PX4_INFO("INFO: payload length invalid, restarting data request");
_parsed_state = 0;
restart_flag = true;
_calc_crc = 0;
break;
} else {
_parsed_state = 3;
break;
}
}
case 3: {
rx_field.msg_id = input_buf[3];
if (rx_field.msg_id == SF_PRODUCT_NAME || rx_field.msg_id == SF_UPDATE_RATE || rx_field.msg_id == SF_DISTANCE_OUTPUT
|| rx_field.msg_id == SF_STREAM || rx_field.msg_id == SF_DISTANCE_DATA_CM) {
if (rx_field.msg_id == SF_DISTANCE_DATA_CM && rx_field.data_len > 1) {
_sensor_ready = true;
} else {
_sensor_ready = false;
}
_calc_crc = sf45_format_crc(_calc_crc, rx_field.msg_id);
_parsed_state = 4;
break;
}
// Ignore message ID's that aren't defined
else {
_parsed_state = 0;
_calc_crc = 0;
restart_flag = true;
break;
}
}
// Data
case 4: {
// Process commands with & w/out data bytes
if (rx_field.data_len > 1) {
for (uint8_t i = 4; i < 3 + rx_field.data_len; ++i) {
rx_field.data[_data_bytes_recv] = input_buf[i];
_calc_crc = sf45_format_crc(_calc_crc, rx_field.data[_data_bytes_recv]);
_data_bytes_recv = _data_bytes_recv + 1;
} // end for
} //end if
else {
_parsed_state = 5;
_data_bytes_recv = 0;
_calc_crc = sf45_format_crc(_calc_crc, _data_bytes_recv);
}
_parsed_state = 5;
_data_bytes_recv = 0;
break;
}
// CRC low byte
case 5: {
rx_field.crc[0] = input_buf[3 + rx_field.data_len];
_parsed_state = 6;
break;
}
// CRC high byte
case 6: {
rx_field.crc[1] = input_buf[4 + rx_field.data_len];
recv_crc = (rx_field.crc[1] << 8) | rx_field.crc[0];
// Check the received crc bytes from the sf45 against our own CRC calcuation
// If it matches, we can check if sensor ready
// Only if crc match is valid and sensor ready (transmitting distance data) do we flag _init_complete
if (recv_crc == _calc_crc) {
_crc_valid = true;
// Sensor is ready if we read msg ID 44: SF_DISTANCE_DATA_CM
if (_sensor_ready) {
_init_complete = true;
} else {
_init_complete = false;
}
_parsed_state = 0;
_calc_crc = 0;
restart_flag = true;
break;
} else {
PX4_INFO("INFO: CRC mismatch");
_crc_valid = false;
_init_complete = false;
_parsed_state = 0;
_calc_crc = 0;
restart_flag = true;
break;
}
}
} // end switch
} //end while
}
void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int *data, uint8_t data_len)
{
uint16_t crc_val = 0;
uint8_t packet_buff[SF45_MAX_PAYLOAD];
uint8_t data_inc = 4;
int ret = 0;
uint8_t packet_len = 0;
// Include payload ID byte in payload len
uint16_t flags = (data_len + 1) << 6;
// If writing to the device, lsb is 1
if (write) {
flags |= 0x01;
}
else {
flags |= 0x0;
}
uint8_t flags_lo = flags & 0xFF;
uint8_t flags_hi = (flags >> 8) & 0xFF;
// Add packet bytes to format into crc based on CRC-16-CCITT 0x1021/XMODEM
crc_val = sf45_format_crc(crc_val, _start_of_frame);
crc_val = sf45_format_crc(crc_val, flags_lo);
crc_val = sf45_format_crc(crc_val, flags_hi);
crc_val = sf45_format_crc(crc_val, msg_id);
// Write the packet header contents + payload msg ID to the output buffer
packet_buff[0] = _start_of_frame;
packet_buff[1] = flags_lo;
packet_buff[2] = flags_hi;
packet_buff[3] = msg_id;
if (msg_id == SF_DISTANCE_OUTPUT) {
uint8_t data_convert = data[0] & 0x00FF;
// write data bytes to the output buffer
packet_buff[data_inc] = data_convert;
// Add data bytes to crc add function
crc_val = sf45_format_crc(crc_val, data_convert);
data_inc = data_inc + 1;
data_convert = data[0] >> 8;
packet_buff[data_inc] = data_convert;
crc_val = sf45_format_crc(crc_val, data_convert);
data_inc = data_inc + 1;
packet_buff[data_inc] = 0;
crc_val = sf45_format_crc(crc_val, packet_buff[data_inc]);
data_inc = data_inc + 1;
packet_buff[data_inc] = 0;
crc_val = sf45_format_crc(crc_val, packet_buff[data_inc]);
data_inc = data_inc + 1;
}
else if (msg_id == SF_STREAM) {
packet_buff[data_inc] = data[0];
//pad zeroes
crc_val = sf45_format_crc(crc_val, data[0]);
data_inc = data_inc + 1;
packet_buff[data_inc] = 0;
crc_val = sf45_format_crc(crc_val, packet_buff[data_inc]);
data_inc = data_inc + 1;
packet_buff[data_inc] = 0;
crc_val = sf45_format_crc(crc_val, packet_buff[data_inc]);
data_inc = data_inc + 1;
packet_buff[data_inc] = 0;
crc_val = sf45_format_crc(crc_val, packet_buff[data_inc]);
data_inc = data_inc + 1;
}
else if (msg_id == SF_UPDATE_RATE) {
// Update Rate
packet_buff[data_inc] = (uint8_t)data[0];
// Add data bytes to crc add function
crc_val = sf45_format_crc(crc_val, data[0]);
data_inc = data_inc + 1;
}
else {
// Product Name
PX4_INFO("INFO: Product name");
}
uint8_t crc_lo = crc_val & 0xFF;
uint8_t crc_hi = (crc_val >> 8) & 0xFF;
packet_buff[data_inc] = crc_lo;
data_inc = data_inc + 1;
packet_buff[data_inc] = crc_hi;
size_t len = sizeof(packet_buff[0]) * (data_inc + 1);
packet_len = (uint8_t)len;
// DEBUG
for (uint8_t i = 0; i < packet_len; ++i) {
PX4_INFO("INFO: Send byte: %d", packet_buff[i]);
}
ret = ::write(_fd, packet_buff, packet_len);
if (ret != packet_len) {
perf_count(_comms_errors);
PX4_DEBUG("write fail %d", ret);
//return ret;
}
}
void SF45LaserSerial::sf45_process_replies(float *distance_m)
{
switch (rx_field.msg_id) {
case SF_DISTANCE_DATA_CM: {
uint16_t obstacle_dist_cm = 0;
const float raw_distance = (rx_field.data[0] << 0) | (rx_field.data[1] << 8);
int16_t raw_yaw = ((rx_field.data[2] << 0) | (rx_field.data[3] << 8));
int16_t scaled_yaw = 0;
// The sensor scans from 0 to -160, so extract negative angle from int16 and represent as if a float
if (raw_yaw > 32000) {
raw_yaw = raw_yaw - 65535;
}
// The sensor is facing downward, so the sensor is flipped about it's x-axis -inverse of each yaw angle
if (_orient_cfg == 1) {
raw_yaw = raw_yaw * -1;
}
switch (_yaw_cfg) {
case 0:
break;
case 1:
if (raw_yaw > 180) {
raw_yaw = raw_yaw - 180;
} else {
raw_yaw = raw_yaw + 180; // rotation facing aft
}
break;
case 2:
raw_yaw = raw_yaw + 90; // rotation facing right
break;
case 3:
raw_yaw = raw_yaw - 90; // rotation facing left
break;
default:
break;
}
scaled_yaw = raw_yaw * SF45_SCALE_FACTOR;
// Convert to meters for rangefinder update
*distance_m = raw_distance * SF45_SCALE_FACTOR;
obstacle_dist_cm = (uint16_t)raw_distance;
uint8_t current_bin = sf45_convert_angle(scaled_yaw);
// If we have moved to a new bin
if (current_bin != _previous_bin) {
// update the current bin to the distance sensor reading
// readings in cm
_obstacle_map_msg.distances[current_bin] = obstacle_dist_cm;
_obstacle_map_msg.timestamp = hrt_absolute_time();
}
_previous_bin = current_bin;
_obstacle_distance_pub.publish(_obstacle_map_msg);
break;
}
default:
// add case for future use
break;
}
}
uint8_t SF45LaserSerial::sf45_convert_angle(const int16_t yaw)
{
uint8_t mapped_sector = 0;
float adjusted_yaw = sf45_wrap_360(yaw - _obstacle_map_msg.angle_offset);
mapped_sector = round(adjusted_yaw / _obstacle_map_msg.increment);
return mapped_sector;
}
float SF45LaserSerial::sf45_wrap_360(float f)
{
return matrix::wrap(f, 0.f, 360.f);
}
uint16_t SF45LaserSerial::sf45_format_crc(uint16_t crc, uint8_t data_val)
{
uint32_t i;
const uint16_t poly = 0x1021u;
crc ^= (uint16_t)((uint16_t) data_val << 8u);
for (i = 0; i < 8; i++) {
if (crc & (1u << 15u)) {
crc = (uint16_t)((crc << 1u) ^ poly);
} else {
crc = (uint16_t)(crc << 1u);
}
}
return crc;
}

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