mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-05 04:00:06 +08:00
Compare commits
113 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| f8a8675e2d | |||
| 600b0e6704 | |||
| 7884e0a3f7 | |||
| f799141a19 | |||
| e20215087f | |||
| 0d0978b3b9 | |||
| 0639f5370c | |||
| 2bacb4b65d | |||
| 421f13e4b5 | |||
| 1e253a9626 | |||
| bb5efa5577 | |||
| 1c741836c0 | |||
| 8b6c70e0f2 | |||
| 1fc38aab92 | |||
| 2bf1eeb003 | |||
| 87960c04d8 | |||
| d96970a2b9 | |||
| c5835a48de | |||
| 6f9a378247 | |||
| 67e68783cf | |||
| d1ae242a91 | |||
| 9cef834624 | |||
| 23a41299fa | |||
| 0186d687b2 | |||
| d28653b605 | |||
| 87d79aeb75 | |||
| 1bd65f8beb | |||
| e0b49afe81 | |||
| f02b44bec5 | |||
| dd67766f6c | |||
| 4a043a80f1 | |||
| bb617a1a56 | |||
| 01de368616 | |||
| 76352765b6 | |||
| 28db3e1c8c | |||
| e9d43015ce | |||
| b46fc9a67d | |||
| b80f15f7b5 | |||
| 086656dc7f | |||
| 051baec9c4 | |||
| 2491548a0f | |||
| 18f96c16ce | |||
| 63495ddac3 | |||
| efbbd64ec0 | |||
| 8001132d33 | |||
| 08a2a6c836 | |||
| d501d8e1d4 | |||
| 9d9766c6cf | |||
| d988005216 | |||
| 5dfdf8c071 | |||
| b2b7439060 | |||
| 37a40d3fc2 | |||
| b405d75553 | |||
| 4e3bd4f196 | |||
| 0cc4b41a51 | |||
| f602228048 | |||
| 9b122adae4 | |||
| 1ec0ba4736 | |||
| 8da8b88a54 | |||
| be08c57a0a | |||
| a436a8f3b8 | |||
| 5ad0e68d8e | |||
| f07eeaa776 | |||
| 506c60c471 | |||
| 643d3e3bf3 | |||
| 8243b4f474 | |||
| 22b957696d | |||
| c338891677 | |||
| c4c41c49e5 | |||
| 021dd0d0af | |||
| c221da27a7 | |||
| 51fe4351c6 | |||
| 8a75733511 | |||
| 1032dd3470 | |||
| 424c3cd2cb | |||
| 68100650da | |||
| 74303a79e1 | |||
| 8dc3975456 | |||
| 84a7d42566 | |||
| f26df8492f | |||
| cb09dde606 | |||
| 1a1891073e | |||
| b8714f8980 | |||
| 0c099f2b56 | |||
| bb53781b8f | |||
| c9ad60e3cc | |||
| a6ef7b6da9 | |||
| 6957818603 | |||
| cb03835124 | |||
| b19e35ec7c | |||
| dce53a626e | |||
| 5f589bdda3 | |||
| 1998f54ea6 | |||
| bef694f9ba | |||
| 560d6a9d4b | |||
| f996caa5bd | |||
| bb0dfba4e6 | |||
| d197d94889 | |||
| 396ef222ee | |||
| f85144ca76 | |||
| b54b4f7dce | |||
| fc90e235f1 | |||
| f7baeae1a0 | |||
| e457a5baed | |||
| 0f3925b21d | |||
| f636414ca7 | |||
| 00a9e4c76b | |||
| 31bbda0b58 | |||
| b355c16141 | |||
| 7fdb5ef3cb | |||
| 3de7d83e5f | |||
| 97cb933cff | |||
| 584d8abe1e |
@@ -120,7 +120,7 @@ pipeline {
|
||||
"px4_fmu-v6xrt_rover",
|
||||
"px4_io-v2_default",
|
||||
"raspberrypi_pico_default",
|
||||
"siyi_n7_default"
|
||||
"siyi_n7_default",
|
||||
"sky-drones_smartap-airlink_default",
|
||||
"spracing_h7extreme_default",
|
||||
"thepeach_k1_default",
|
||||
|
||||
@@ -25,6 +25,7 @@ jobs:
|
||||
ark_can-rtk-gps,
|
||||
ark_cannode,
|
||||
ark_fmu-v6x,
|
||||
ark_septentrio-gps,
|
||||
atl_mantis-edu,
|
||||
av_x-v1,
|
||||
bitcraze_crazyflie,
|
||||
|
||||
Vendored
+10
@@ -151,6 +151,16 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_can-rtk-gps_canbootloader
|
||||
ark_septentrio_gps_default:
|
||||
short: ark_septentrio_gps_default
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_septentrio_gps_default
|
||||
ark_septentrio_gps_canbootloader:
|
||||
short: ark_septentrio_gps_canbootloader
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_septentrio_gps_canbootloader
|
||||
ark_cannode_default:
|
||||
short: ark_cannode_default
|
||||
buildType: MinSizeRel
|
||||
|
||||
@@ -0,0 +1,80 @@
|
||||
#!/bin/sh
|
||||
# @name Gazebo lawnmower
|
||||
# @type Rover
|
||||
# @class Rover
|
||||
|
||||
. ${R}etc/init.d/rc.rover_differential_defaults
|
||||
|
||||
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
|
||||
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
|
||||
PX4_SIM_MODEL=${PX4_SIM_MODEL:=lawnmower}
|
||||
|
||||
param set-default SIM_GZ_EN 1 # Gazebo bridge
|
||||
|
||||
# Simulated sensors
|
||||
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
|
||||
# We can arm and drive in manual mode when it slides and GPS check fails:
|
||||
param set-default COM_ARM_WO_GPS 1
|
||||
|
||||
# Set Differential Drive Kinematics Library parameters:
|
||||
param set RDD_WHEEL_BASE 0.9
|
||||
param set RDD_WHEEL_RADIUS 0.22
|
||||
param set RDD_WHEEL_SPEED 10.0 # Maximum wheel speed rad/s, approx 8 km/h
|
||||
|
||||
# Actuator mapping - set SITL motors/servos output parameters:
|
||||
|
||||
# "Motors" - motor channels 0 (Right) and 1 (Left) - via Wheels GZ bridge:
|
||||
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
|
||||
#param set-default SIM_GZ_WH_MIN1 0
|
||||
#param set-default SIM_GZ_WH_MAX1 200
|
||||
#param set-default SIM_GZ_WH_DIS1 100
|
||||
#param set-default SIM_GZ_WH_FAIL1 100
|
||||
|
||||
param set-default SIM_GZ_WH_FUNC2 102 # left wheel
|
||||
#param set-default SIM_GZ_WH_MIN2 0
|
||||
#param set-default SIM_GZ_WH_MAX2 200
|
||||
#aram set-default SIM_GZ_WH_DIS2 100
|
||||
#param set-default SIM_GZ_WH_FAIL2 100
|
||||
|
||||
param set-default SIM_GZ_WH_REV 0 # no need to reverse any wheels
|
||||
|
||||
# Note: The servo configurations ( SIM_GZ_SV_FUNC*) outlined below are intended for educational purposes in this simulation.
|
||||
# They do not have physical effects in the simulated environment, except for actuating the joints. Their definitions are meant to demonstrate
|
||||
# how actuators could be mapped and configured in a real-world application, providing a foundation for understanding and implementing actuator
|
||||
# controls in practical scenarios.
|
||||
|
||||
# Cutter deck blades clutch, PCA9685 servo channel 3, "RC FLAPS" (406) - leftmost switch, or "Servo 3" (203):
|
||||
param set-default SIM_GZ_SV_FUNC3 203
|
||||
param set-default SIM_GZ_SV_MIN3 0
|
||||
param set-default SIM_GZ_SV_MAX3 1000
|
||||
param set-default SIM_GZ_SV_DIS3 500
|
||||
param set-default SIM_GZ_SV_FAIL3 500
|
||||
|
||||
# Gas engine throttle, PCA9685 servo channel 4, "RC AUX1" (407) - left knob, or "Servo 4" (204):
|
||||
# - on minimum when disarmed or failed:
|
||||
param set-default SIM_GZ_SV_FUNC4 204
|
||||
param set-default SIM_GZ_SV_MIN4 0
|
||||
param set-default SIM_GZ_SV_MAX4 1000
|
||||
param set-default SIM_GZ_SV_DIS4 500
|
||||
param set-default SIM_GZ_SV_FAIL4 500
|
||||
|
||||
# Controlling PCA9685 servos 5,6,7,8 directly via "Servo 5..8" setting, by publishing actuator_servos.control[]:
|
||||
|
||||
# Strobes, PCA9685 servo channel 5, "Servo 5" (205) - flashing indicates Mission mode:
|
||||
#param set-default SIM_GZ_SV_FUNC5 205
|
||||
#param set-default SIM_GZ_SV_MIN5 1000
|
||||
#param set-default SIM_GZ_SV_MAX5 2000
|
||||
#param set-default SIM_GZ_SV_DIS5 1000
|
||||
#param set-default SIM_GZ_SV_FAIL5 1000
|
||||
|
||||
# Horn, PCA9685 servo channel 6, "Servo 6" (206) - for alarms like GPS failure:
|
||||
#param set-default SIM_GZ_SV_FUNC6 206
|
||||
|
||||
# Spare PCA9685 servo channel 7 on "RC AUX2" (408) - right knob, or "Servo 7" (207):
|
||||
#param set-default SIM_GZ_SV_FUNC7 207
|
||||
|
||||
# Spare PCA9685 servo channel 8 - "Servo 8" (208):
|
||||
#param set-default SIM_GZ_SV_FUNC8 208
|
||||
@@ -82,6 +82,7 @@ px4_add_romfs_files(
|
||||
4008_gz_advanced_plane
|
||||
4009_gz_r1_rover
|
||||
4010_gz_x500_mono_cam
|
||||
4011_gz_lawnmower
|
||||
|
||||
6011_gazebo-classic_typhoon_h480
|
||||
6011_gazebo-classic_typhoon_h480.post
|
||||
|
||||
@@ -41,19 +41,6 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
|
||||
echo "INFO [init] Gazebo simulator"
|
||||
|
||||
# set local coordinate frame reference
|
||||
if [ -n "${PX4_HOME_LAT}" ]; then
|
||||
param set SIM_GZ_HOME_LAT ${PX4_HOME_LAT}
|
||||
fi
|
||||
|
||||
if [ -n "${PX4_HOME_LON}" ]; then
|
||||
param set SIM_GZ_HOME_LON ${PX4_HOME_LON}
|
||||
fi
|
||||
|
||||
if [ -n "${PX4_HOME_ALT}" ]; then
|
||||
param set SIM_GZ_HOME_ALT ${PX4_HOME_ALT}
|
||||
fi
|
||||
|
||||
# Only start up Gazebo if PX4_GZ_STANDALONE is not set.
|
||||
if [ -z "${PX4_GZ_STANDALONE}" ]; then
|
||||
|
||||
@@ -180,6 +167,12 @@ elif [ "$PX4_SIM_MODEL" = "jmavsim_iris" ] || [ "$(param show -q SYS_AUTOSTART)"
|
||||
|
||||
else
|
||||
# otherwise start simulator (mavlink) module
|
||||
|
||||
# EKF2 specifics
|
||||
param set-default EKF2_GPS_DELAY 10
|
||||
param set-default EKF2_MULTI_IMU 3
|
||||
param set-default SENS_IMU_MODE 0
|
||||
|
||||
simulator_tcp_port=$((4560+px4_instance))
|
||||
|
||||
# Check if PX4_SIM_HOSTNAME environment variable is empty
|
||||
|
||||
@@ -164,10 +164,6 @@ param set-default COM_RC_IN_MODE 1
|
||||
# Speedup SITL startup
|
||||
param set-default EKF2_REQ_GPS_H 0.5
|
||||
|
||||
# Multi-EKF
|
||||
param set-default EKF2_MULTI_IMU 3
|
||||
param set-default SENS_IMU_MODE 0
|
||||
|
||||
param set-default IMU_GYRO_FFT_EN 1
|
||||
param set-default MAV_PROTO_VER 2 # Ensures QGC does not drop the first few packets after a SITL restart due to MAVLINK 1 packets
|
||||
|
||||
|
||||
@@ -34,28 +34,79 @@
|
||||
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
|
||||
rc.fw_apps
|
||||
rc.fw_defaults
|
||||
rc.heli_defaults
|
||||
rc.logging
|
||||
rc.mc_apps
|
||||
rc.mc_defaults
|
||||
|
||||
rcS
|
||||
rc.sensors
|
||||
rc.thermal_cal
|
||||
rc.rover_apps
|
||||
rc.rover_defaults
|
||||
rc.rover_differential_apps
|
||||
rc.rover_differential_defaults
|
||||
rc.uuv_apps
|
||||
rc.uuv_defaults
|
||||
rc.vehicle_setup
|
||||
rc.vtol_apps
|
||||
rc.vtol_defaults
|
||||
|
||||
# TODO
|
||||
rc.balloon_apps
|
||||
rc.balloon_defaults
|
||||
)
|
||||
|
||||
if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.airship_apps
|
||||
rc.airship_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_FW_RATE_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.fw_apps
|
||||
rc.fw_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_MC_RATE_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.heli_defaults
|
||||
rc.mc_apps
|
||||
rc.mc_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_ROVER_POS_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.rover_apps
|
||||
rc.rover_defaults
|
||||
|
||||
rc.boat_defaults # hack
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_DIFFERENTIAL_DRIVE)
|
||||
px4_add_romfs_files(
|
||||
rc.rover_differential_apps
|
||||
rc.rover_differential_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_UUV_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.uuv_apps
|
||||
rc.uuv_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_VTOL_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
rc.vtol_apps
|
||||
rc.vtol_defaults
|
||||
)
|
||||
endif()
|
||||
|
||||
|
||||
if(CONFIG_MODULES_LOGGER)
|
||||
px4_add_romfs_files(
|
||||
rc.logging
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_TEMPERATURE_COMPENSATION)
|
||||
px4_add_romfs_files(
|
||||
rc.thermal_cal
|
||||
)
|
||||
endif()
|
||||
|
||||
@@ -32,94 +32,127 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_romfs_files(
|
||||
# [0-999] Reserved (historical)"
|
||||
|
||||
# [1000, 1999] Simulation setups"
|
||||
1001_rc_quad_x.hil
|
||||
1002_standard_vtol.hil
|
||||
1100_rc_quad_x_sih.hil
|
||||
1101_rc_plane_sih.hil
|
||||
1102_tailsitter_duo_sih.hil
|
||||
|
||||
# [2000, 2999] Standard planes"
|
||||
2100_standard_plane
|
||||
2106_albatross
|
||||
|
||||
2507_cloudship
|
||||
|
||||
# [3000, 3999] Flying wing"
|
||||
3000_generic_wing
|
||||
|
||||
# [4000, 4999] Quadrotor x"
|
||||
4001_quad_x
|
||||
4014_s500
|
||||
4015_holybro_s500
|
||||
4016_holybro_px4vision
|
||||
4017_nxp_hovergames
|
||||
4019_x500_v2
|
||||
4020_holybro_px4vision_v1_5
|
||||
4041_beta75x
|
||||
4050_generic_250
|
||||
4052_holybro_qav250
|
||||
4053_holybro_kopis2
|
||||
4061_atl_mantis_edu
|
||||
4071_ifo
|
||||
4073_ifo-s
|
||||
4500_clover4
|
||||
4901_crazyflie21
|
||||
|
||||
# [5000, 5999] Quadrotor +"
|
||||
5001_quad_+
|
||||
|
||||
# [6000, 6999] Hexarotor x"
|
||||
6001_hexa_x
|
||||
6002_draco_r
|
||||
|
||||
# [7000, 7999] Hexarotor +"
|
||||
7001_hexa_+
|
||||
|
||||
# [8000, 8999] Octorotor +"
|
||||
8001_octo_x
|
||||
|
||||
# [9000, 9999] Octorotor +"
|
||||
9001_octo_+
|
||||
|
||||
# [11000, 11999] Hexa Cox
|
||||
11001_hexa_cox
|
||||
|
||||
# [12000, 12999] Octo Cox
|
||||
12001_octo_cox
|
||||
|
||||
# [13000, 13999] VTOL
|
||||
13000_generic_vtol_standard
|
||||
13100_generic_vtol_tiltrotor
|
||||
13013_deltaquad
|
||||
13014_vtol_babyshark
|
||||
13030_generic_vtol_quad_tiltrotor
|
||||
13200_generic_vtol_tailsitter
|
||||
|
||||
# [14000, 14999] MC with tilt
|
||||
14001_generic_mc_with_tilt
|
||||
|
||||
16001_helicopter
|
||||
|
||||
# [17000, 17999] Autogyro
|
||||
17002_TF-AutoG2
|
||||
17003_TF-G2
|
||||
# [0-999] Reserved (historical)
|
||||
|
||||
# [18000, 18999] High-altitude balloons
|
||||
18001_TF-B1
|
||||
|
||||
# [22000, 22999] Reserve for custom models
|
||||
|
||||
24001_dodeca_cox
|
||||
|
||||
50000_generic_ground_vehicle
|
||||
50004_nxpcup_car_dfrobot_gpx
|
||||
50003_aion_robotics_r1_rover
|
||||
|
||||
# [60000, 61000] (Unmanned) Underwater Robots
|
||||
60000_uuv_generic
|
||||
60001_uuv_hippocampus
|
||||
60002_uuv_bluerov2_heavy
|
||||
)
|
||||
|
||||
if(CONFIG_MODULES_SIMULATION_PWM_OUT_SIM)
|
||||
px4_add_romfs_files(
|
||||
# [1000, 1999] Simulation setups
|
||||
1001_rc_quad_x.hil
|
||||
1002_standard_vtol.hil
|
||||
1100_rc_quad_x_sih.hil
|
||||
1101_rc_plane_sih.hil
|
||||
1102_tailsitter_duo_sih.hil
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_MC_RATE_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
# [4000, 4999] Quadrotor x
|
||||
4001_quad_x
|
||||
4014_s500
|
||||
4015_holybro_s500
|
||||
4016_holybro_px4vision
|
||||
4017_nxp_hovergames
|
||||
4019_x500_v2
|
||||
4020_holybro_px4vision_v1_5
|
||||
4041_beta75x
|
||||
4050_generic_250
|
||||
4052_holybro_qav250
|
||||
4053_holybro_kopis2
|
||||
4061_atl_mantis_edu
|
||||
4071_ifo
|
||||
4073_ifo-s
|
||||
4500_clover4
|
||||
4901_crazyflie21
|
||||
|
||||
# [5000, 5999] Quadrotor +
|
||||
5001_quad_+
|
||||
|
||||
# [6000, 6999] Hexarotor x
|
||||
6001_hexa_x
|
||||
6002_draco_r
|
||||
|
||||
# [7000, 7999] Hexarotor +
|
||||
7001_hexa_+
|
||||
|
||||
# [8000, 8999] Octorotor +
|
||||
8001_octo_x
|
||||
|
||||
# [9000, 9999] Octorotor +
|
||||
9001_octo_+
|
||||
|
||||
# [11000, 11999] Hexa Cox
|
||||
11001_hexa_cox
|
||||
|
||||
# [12000, 12999] Octo Cox
|
||||
12001_octo_cox
|
||||
|
||||
# [14000, 14999] MC with tilt
|
||||
14001_generic_mc_with_tilt
|
||||
|
||||
16001_helicopter
|
||||
|
||||
24001_dodeca_cox
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_FW_RATE_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
# [2000, 2999] Standard planes
|
||||
2100_standard_plane
|
||||
2106_albatross
|
||||
|
||||
# [3000, 3999] Flying wing
|
||||
3000_generic_wing
|
||||
|
||||
# [17000, 17999] Autogyro
|
||||
17002_TF-AutoG2
|
||||
17003_TF-G2
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
2507_cloudship
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_VTOL_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
# [13000, 13999] VTOL
|
||||
13000_generic_vtol_standard
|
||||
13100_generic_vtol_tiltrotor
|
||||
13013_deltaquad
|
||||
13014_vtol_babyshark
|
||||
13030_generic_vtol_quad_tiltrotor
|
||||
13200_generic_vtol_tailsitter
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_ROVER_POS_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
50000_generic_ground_vehicle
|
||||
50004_nxpcup_car_dfrobot_gpx
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_DIFFERENTIAL_DRIVE)
|
||||
px4_add_romfs_files(
|
||||
50003_aion_robotics_r1_rover
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_MODULES_UUV_ATT_CONTROL)
|
||||
px4_add_romfs_files(
|
||||
# [60000, 61000] (Unmanned) Underwater Robots
|
||||
60000_uuv_generic
|
||||
60001_uuv_hippocampus
|
||||
60002_uuv_bluerov2_heavy
|
||||
)
|
||||
endif()
|
||||
|
||||
@@ -28,7 +28,6 @@ param set-default EKF2_ARSP_THR 8
|
||||
param set-default EKF2_FUSE_BETA 1
|
||||
param set-default EKF2_GPS_CHECK 21
|
||||
param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_MAG_YAWLIM 0
|
||||
param set-default EKF2_REQ_EPH 10
|
||||
param set-default EKF2_REQ_EPV 10
|
||||
param set-default EKF2_REQ_HDRIFT 0.5
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
ekf2 start &
|
||||
|
||||
# Start rover differential drive controller.
|
||||
differential_drive_control start
|
||||
differential_drive start
|
||||
|
||||
# Start Land Detector.
|
||||
land_detector start rover
|
||||
|
||||
@@ -439,7 +439,12 @@ else
|
||||
#
|
||||
# Start a thermal calibration if required.
|
||||
#
|
||||
. ${R}etc/init.d/rc.thermal_cal
|
||||
set RC_THERMAL_CAL ${R}etc/init.d/rc.thermal_cal
|
||||
if [ -f ${RC_THERMAL_CAL} ]
|
||||
then
|
||||
. ${RC_THERMAL_CAL}
|
||||
fi
|
||||
unset RC_THERMAL_CAL
|
||||
|
||||
#
|
||||
# Start gimbal to control mounts such as gimbals, disabled by default.
|
||||
@@ -500,7 +505,12 @@ else
|
||||
#
|
||||
# Start the logger.
|
||||
#
|
||||
. ${R}etc/init.d/rc.logging
|
||||
set RC_LOGGING ${R}etc/init.d/rc.logging
|
||||
if [ -f ${RC_LOGGING} ]
|
||||
then
|
||||
. ${RC_LOGGING}
|
||||
fi
|
||||
unset RC_LOGGING
|
||||
|
||||
#
|
||||
# Set additional parameters and env variables for selected AUTOSTART.
|
||||
|
||||
@@ -30,4 +30,5 @@ exec find boards msg src platforms test \
|
||||
-path src/lib/cdrstream/cyclonedds -prune -o \
|
||||
-path src/lib/cdrstream/rosidl -prune -o \
|
||||
-path src/modules/zenoh/zenoh-pico -prune -o \
|
||||
-path src/modules/muorb/apps/libfc-sensor-api -prune -o \
|
||||
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN
|
||||
|
||||
@@ -73,9 +73,16 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
@{
|
||||
queue_length = 1
|
||||
for constant in spec.constants:
|
||||
if constant.name == 'ORB_QUEUE_LENGTH':
|
||||
queue_length = constant.val
|
||||
}@
|
||||
|
||||
@[for topic in topics]@
|
||||
static_assert(static_cast<orb_id_size_t>(ORB_ID::@topic) == @(all_topics.index(topic)), "ORB_ID index mismatch");
|
||||
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic));
|
||||
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic), @queue_length);
|
||||
@[end for]
|
||||
|
||||
void print_message(const orb_metadata *meta, const @uorb_struct& message)
|
||||
|
||||
Submodule Tools/simulation/gazebo-classic/sitl_gazebo-classic updated: 33ac87a376...da7206e057
+1
-1
Submodule Tools/simulation/gz updated: c78f7f0141...6b4ed09d1b
@@ -0,0 +1,5 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
|
||||
CONFIG_BOARD_ROMFSROOT=""
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_DRIVERS_BOOTLOADERS=y
|
||||
@@ -0,0 +1,37 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
|
||||
CONFIG_BOARD_ROMFSROOT="cannode"
|
||||
CONFIG_BOARD_NO_HELP=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BOOTLOADERS=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
CONFIG_DRIVERS_UAVCANNODE=y
|
||||
CONFIG_UAVCANNODE_BEEP_COMMAND=y
|
||||
CONFIG_UAVCANNODE_GNSS_FIX=y
|
||||
CONFIG_UAVCANNODE_LIGHTS_COMMAND=y
|
||||
CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y
|
||||
CONFIG_UAVCANNODE_RTK_DATA=y
|
||||
CONFIG_UAVCANNODE_SAFETY_BUTTON=y
|
||||
CONFIG_UAVCANNODE_STATIC_PRESSURE=y
|
||||
CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
|
||||
# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set
|
||||
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 84,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the ARK Septentrio GPS board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "ARKSEPTENTRIOGPS",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2080768,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,13 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default CBRK_IO_SAFETY 0
|
||||
param set-default CANNODE_SUB_MBD 1
|
||||
param set-default CANNODE_SUB_RTCM 1
|
||||
param set-default MBE_ENABLE 1
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
safety_button start
|
||||
tone_alarm start
|
||||
@@ -0,0 +1,11 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
gps start -d /dev/ttyS0 -p sbf
|
||||
|
||||
icm42688p -R 0 -s start
|
||||
|
||||
bmp388 -I -b 1 start
|
||||
|
||||
bmm150 -I -b 1 start
|
||||
@@ -0,0 +1,56 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/septentrio-gps/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F412CE=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=4096
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BINFMT_DISABLE=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DISABLE_MOUNTPOINT=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FDCLONE_DISABLE=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=4096
|
||||
CONFIG_INIT_STACKSIZE=4096
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_NAME_MAX=0
|
||||
CONFIG_NUNGET_CHARS=0
|
||||
CONFIG_PREALLOC_TIMERS=0
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_DISABLE_BUFFERING=y
|
||||
CONFIG_STM32_NOEXT_VECTORS=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_TASK_NAME_SIZE=0
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
@@ -0,0 +1,152 @@
|
||||
/************************************************************************************
|
||||
* configs/px4fmu/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX 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 "board_dma_map.h"
|
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H
|
||||
#define __ARCH_BOARD_BOARD_H
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include <stm32.h>
|
||||
|
||||
/* HSI - 8 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC
|
||||
* HSE - 8 MHz Crystal
|
||||
* LSE - not installed
|
||||
*/
|
||||
#define STM32_BOARD_USEHSE 1
|
||||
#define STM32_BOARD_XTAL 8000000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
|
||||
/* Main PLL Configuration */
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8)
|
||||
#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
|
||||
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/
|
||||
|
||||
#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL
|
||||
#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ
|
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 96000000ul
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (96MHz) */
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK (96MHz) */
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY)
|
||||
|
||||
/* Timers driven from APB2 will be PCLK2 since no prescale division */
|
||||
#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */
|
||||
#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY)
|
||||
#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/* UARTs */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_1
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_1
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_1
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_1
|
||||
|
||||
/* I2C */
|
||||
|
||||
#define GPIO_MCU_I2C1_SCL
|
||||
#define GPIO_MCU_I2C1_SDA
|
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
|
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_4
|
||||
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
|
||||
#endif /* __ARCH_BOARD_BOARD_H */
|
||||
@@ -0,0 +1,46 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
// DMA1 Channel/Stream Selections
|
||||
//--------------------------------------------//---------------------------//----------------
|
||||
|
||||
|
||||
// DMA2 Channel/Stream Selections
|
||||
//--------------------------------------------//---------------------------//----------------
|
||||
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3
|
||||
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3
|
||||
#define DMACHAN_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1
|
||||
//#define DMACHAN_USART1_TX DMAMAP_USART1_TX // DMA2, Stream 7, Channel 4
|
||||
@@ -0,0 +1,152 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD 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_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_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_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/ark/septentrio-gps/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F412CE=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=2624
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=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_WAITPID=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_PREFETCH=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2C2=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART_BREAKS=y
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=2000
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_TXBUFSIZE=2000
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_SERIAL_CONSOLE=y
|
||||
CONFIG_USART2_TXBUFSIZE=1100
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
@@ -0,0 +1,134 @@
|
||||
/****************************************************************************
|
||||
* nuttx-config/scripts/canbootloader_script.ld
|
||||
*
|
||||
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of SRAM beginning at address 0x2002:0000
|
||||
* 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* The first 0x10000 of flash is reserved for the bootloader.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
|
||||
EXTERN(_vectors) /* force the vectors to be included in the output */
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > flash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,146 @@
|
||||
/****************************************************************************
|
||||
* scripts/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of SRAM beginning at address 0x2002:0000
|
||||
* 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* The first 0x10000 of flash is reserved for the bootloader.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
|
||||
EXTERN(_vectors) /* force the vectors to be included in the output */
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(8);
|
||||
/*
|
||||
* This section positions the app_descriptor_t used
|
||||
* by the make_can_boot_descriptor.py tool to set
|
||||
* the application image's descriptor so that the
|
||||
* uavcan bootloader has the ability to validate the
|
||||
* image crc, size etc
|
||||
*/
|
||||
KEEP(*(.app_descriptor))
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > flash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,67 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
||||
|
||||
add_library(drivers_board
|
||||
boot_config.h
|
||||
boot.c
|
||||
led.c
|
||||
led.h
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
canbootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
spi.cpp
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_spi
|
||||
drivers__led # drv_led_start
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
px4_layer
|
||||
)
|
||||
endif()
|
||||
@@ -0,0 +1,125 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* board internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/* BUTTON */
|
||||
#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15)
|
||||
|
||||
/* Safety LED */
|
||||
#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1)
|
||||
|
||||
/* Tone alarm output. */
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* channel 1 */
|
||||
#define GPIO_TONE_ALARM_IDLE /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TONE_ALARM /* PA0 */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
/* CAN Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
|
||||
|
||||
/* CAN termination software control */
|
||||
#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
|
||||
|
||||
/* ICM42688p FSYNC */
|
||||
#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
/* Boot config */
|
||||
#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI)
|
||||
|
||||
/* LEDs are driven with open drain to support Anode to 5V or 3.3V */
|
||||
#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
|
||||
#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
|
||||
#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz)
|
||||
|
||||
#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
|
||||
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer 3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
GPIO_BTN_SAFETY, \
|
||||
GPIO_LED_SAFETY, \
|
||||
GPIO_I2C1_SCL_RESET, \
|
||||
GPIO_I2C1_SDA_RESET, \
|
||||
GPIO_I2C2_SCL_RESET, \
|
||||
GPIO_I2C2_SDA_RESET, \
|
||||
GPIO_42688P_FSYNC, \
|
||||
GPIO_BOOT_CONFIG, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_CAN1_TERMINATION, \
|
||||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
#define BOARD_HAS_N_S_RGB_LED 1
|
||||
#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,188 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
* Author: Ben Dyer <ben_dyer@mac.com>
|
||||
* Pavel Kirienko <pavel.kirienko@zubax.com>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <stdint.h>
|
||||
#include "boot_config.h"
|
||||
#include "board.h"
|
||||
|
||||
#include <debug.h>
|
||||
#include <string.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include "led.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
|
||||
stm32_configgpio(GPIO_CAN1_RX);
|
||||
stm32_configgpio(GPIO_CAN1_TX);
|
||||
stm32_configgpio(GPIO_CAN1_SILENT_S0);
|
||||
stm32_configgpio(GPIO_CAN1_TERMINATION);
|
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
|
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
|
||||
|
||||
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
|
||||
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_deinitialize
|
||||
*
|
||||
* Description:
|
||||
* This function is called by the bootloader code prior to booting
|
||||
* the application. Is should place the HW into an benign initialized state.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void board_deinitialize(void)
|
||||
{
|
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_get_product_name
|
||||
*
|
||||
* Description:
|
||||
* Called to retrieve the product name. The returned value is a assumed
|
||||
* to be written to a pascal style string that will be length prefixed
|
||||
* and not null terminated
|
||||
*
|
||||
* Input Parameters:
|
||||
* product_name - A pointer to a buffer to write the name.
|
||||
* maxlen - The maximum number of charter that can be written
|
||||
*
|
||||
* Returned Value:
|
||||
* The length of characters written to the buffer.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
|
||||
{
|
||||
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
|
||||
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
|
||||
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_get_hardware_version
|
||||
*
|
||||
* Description:
|
||||
* Called to retrieve the hardware version information. The function
|
||||
* will first initialize the the callers struct to all zeros.
|
||||
*
|
||||
* Input Parameters:
|
||||
* hw_version - A pointer to a uavcan_hardwareversion_t.
|
||||
*
|
||||
* Returned Value:
|
||||
* Length of the unique_id
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
|
||||
{
|
||||
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
|
||||
|
||||
hw_version->major = HW_VERSION_MAJOR;
|
||||
hw_version->minor = HW_VERSION_MINOR;
|
||||
|
||||
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_indicate
|
||||
*
|
||||
* Description:
|
||||
* Provides User feedback to indicate the state of the bootloader
|
||||
* on board specific hardware.
|
||||
*
|
||||
* Input Parameters:
|
||||
* indication - A member of the uiindication_t
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
|
||||
|
||||
typedef begin_packed_struct struct led_t {
|
||||
uint8_t red;
|
||||
uint8_t green;
|
||||
uint8_t blue;
|
||||
uint8_t hz;
|
||||
} end_packed_struct led_t;
|
||||
|
||||
static const led_t i2l[] = {
|
||||
|
||||
led(0, off, 0, 0, 0, 0),
|
||||
led(1, reset, 128, 128, 128, 30),
|
||||
led(2, autobaud_start, 0, 128, 0, 1),
|
||||
led(3, autobaud_end, 0, 128, 0, 2),
|
||||
led(4, allocation_start, 0, 0, 64, 2),
|
||||
led(5, allocation_end, 0, 128, 64, 3),
|
||||
led(6, fw_update_start, 32, 128, 64, 3),
|
||||
led(7, fw_update_erase_fail, 32, 128, 32, 3),
|
||||
led(8, fw_update_invalid_response, 64, 0, 0, 1),
|
||||
led(9, fw_update_timeout, 64, 0, 0, 2),
|
||||
led(a, fw_update_invalid_crc, 64, 0, 0, 4),
|
||||
led(b, jump_to_app, 0, 128, 0, 10),
|
||||
|
||||
};
|
||||
|
||||
void board_indicate(uiindication_t indication)
|
||||
{
|
||||
rgb_led(i2l[indication].red,
|
||||
i2l[indication].green,
|
||||
i2l[indication].blue,
|
||||
i2l[indication].hz);
|
||||
}
|
||||
@@ -0,0 +1,130 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file boot_config.h
|
||||
*
|
||||
* bootloader definitions that configures the behavior and options
|
||||
* of the Boot loader
|
||||
* This file is relies on the parent folder's boot_config.h file and defines
|
||||
* different usages of the hardware for bootloading
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
/* Bring in the board_config.h definitions
|
||||
* todo:make this be pulled in from a targed's build
|
||||
* files in nuttx*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include "uavcan.h"
|
||||
#include <nuttx/compiler.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32_flash.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
|
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 3000
|
||||
#define OPT_NODE_STATUS_RATE_MS 800
|
||||
#define OPT_NODE_INFO_RATE_MS 50
|
||||
#define OPT_BL_NUMBER_TIMERS 7
|
||||
|
||||
/*
|
||||
* This Option set is set to 1 ensure a provider of firmware has an
|
||||
* opportunity update the node's firmware.
|
||||
* This Option is the default policy and can be overridden by
|
||||
* a jumper
|
||||
* When this Policy is set, the node will ignore tboot and
|
||||
* wait indefinitely for a GetNodeInfo request before booting.
|
||||
*
|
||||
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
|
||||
* the polarity of the jumper to be True Active
|
||||
*
|
||||
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
|
||||
* Jumper
|
||||
* yes 1 0 x
|
||||
* yes 1 1 Active
|
||||
* no 1 1 Not Active
|
||||
* no 0 0 X
|
||||
* yes 0 1 Active
|
||||
* no 0 1 Not Active
|
||||
*
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO 0
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
|
||||
|
||||
#define OPT_ENABLE_WD 1
|
||||
|
||||
#define OPT_RESTART_TIMEOUT_MS 20000
|
||||
|
||||
/* Reserved for the Booloader */
|
||||
#define OPT_BOOTLOADER_SIZE_IN_K (1024*64)
|
||||
|
||||
/* Reserved for the application out of the total
|
||||
* system flash minus the BOOTLOADER_SIZE_IN_K
|
||||
*/
|
||||
#define OPT_APPLICATION_RESERVER_IN_K 0
|
||||
|
||||
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
|
||||
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
|
||||
|
||||
|
||||
#define FLASH_BASE STM32_FLASH_BASE
|
||||
#define FLASH_SIZE STM32_FLASH_SIZE
|
||||
|
||||
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
|
||||
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
|
||||
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
|
||||
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
|
||||
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
|
||||
|
||||
/* If this board uses big flash that have large sectors */
|
||||
|
||||
#define OPT_USE_YIELD
|
||||
|
||||
/* Bootloader Option*****************************************************************
|
||||
*
|
||||
*/
|
||||
#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI)
|
||||
@@ -0,0 +1,130 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "arm_internal.h"
|
||||
|
||||
#include "stm32.h"
|
||||
#include "stm32_can.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2021 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 <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusInternal(1),
|
||||
initI2CBusInternal(2),
|
||||
};
|
||||
@@ -0,0 +1,168 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* board specific early startup code. This file implements the
|
||||
* board_app_initialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialization.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <syslog.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include "led.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <drivers/drv_watchdog.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
|
||||
# if defined(FLASH_BASED_PARAMS)
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
watchdog_init();
|
||||
|
||||
/* configure pins */
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
// Configure SPI all interfaces GPIO & enable power.
|
||||
stm32_spiinitialize();
|
||||
|
||||
// Check if button is held. If so go into gps passthrough mode
|
||||
if (stm32_gpioread(GPIO_BTN_SAFETY)) {
|
||||
rgb_led(128, 128, 128, 10);
|
||||
stm32_configgpio(GPIO_USART1_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART1_RX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_RX_GPIO);
|
||||
|
||||
while (1) {
|
||||
watchdog_pet();
|
||||
stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
|
||||
stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||
* implementation without modification. The argument has no
|
||||
* meaning to NuttX; the meaning of the argument is a contract
|
||||
* between the board-specific initalization logic and the the
|
||||
* matching application logic. The value cold be such things as a
|
||||
* mode enumeration value, a set of DIP switch switch settings, a
|
||||
* pointer to configuration data read from a file or serial FLASH,
|
||||
* or whatever you would like to do with it. Every implementation
|
||||
* should accept zero/NULL as a default configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
px4_platform_init();
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
|
||||
#endif
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{2, 16 * 1024, 0x08008000},
|
||||
{3, 16 * 1024, 0x0800C000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
/* Initialize the flashfs layer to use heap allocated memory */
|
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
//px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,124 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "led.h"
|
||||
|
||||
#define TMR_BASE STM32_TIM1_BASE
|
||||
#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
|
||||
#define TMR_REG(o) (TMR_BASE+(o))
|
||||
|
||||
void rgb_led(int r, int g, int b, int freqs)
|
||||
{
|
||||
|
||||
long fosc = TMR_FREQUENCY;
|
||||
long prescale = 2048;
|
||||
long p1s = fosc / prescale;
|
||||
long p0p5s = p1s / 2;
|
||||
uint16_t val;
|
||||
static bool once = 0;
|
||||
|
||||
if (!once) {
|
||||
once = 1;
|
||||
|
||||
/* Enabel Clock to Block */
|
||||
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
|
||||
|
||||
/* Reload */
|
||||
|
||||
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
|
||||
val |= ATIM_EGR_UG;
|
||||
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
|
||||
|
||||
/* Set Prescaler STM32_TIM_SETCLOCK */
|
||||
|
||||
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
|
||||
|
||||
/* Enable STM32_TIM_SETMODE*/
|
||||
|
||||
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
|
||||
|
||||
|
||||
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
|
||||
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
|
||||
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
|
||||
putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
|
||||
ATIM_CCER_CC2E | ATIM_CCER_CC2P |
|
||||
ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
|
||||
|
||||
|
||||
stm32_configgpio(GPIO_TIM1_CH1);
|
||||
stm32_configgpio(GPIO_TIM1_CH2);
|
||||
stm32_configgpio(GPIO_TIM1_CH3);
|
||||
|
||||
/* master output enable = on */
|
||||
putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET)));
|
||||
}
|
||||
|
||||
long p = freqs == 0 ? p1s : p1s / freqs;
|
||||
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
|
||||
|
||||
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
|
||||
|
||||
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
|
||||
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
|
||||
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
|
||||
|
||||
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
|
||||
|
||||
if (freqs == 0) {
|
||||
val &= ~ATIM_CR1_CEN;
|
||||
|
||||
} else {
|
||||
val |= ATIM_CR1_CEN;
|
||||
}
|
||||
|
||||
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
|
||||
|
||||
}
|
||||
@@ -0,0 +1,37 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane<david_s5@nscdg.com>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__BEGIN_DECLS
|
||||
void rgb_led(int r, int g, int b, int freqs);
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,44 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2021 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 <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin0}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,17 @@
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
|
||||
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
)
|
||||
|
||||
set(uavcanblid_hw_version_major 0)
|
||||
set(uavcanblid_hw_version_minor 84)
|
||||
set(uavcanblid_name "\"org.ark.septentrio-gps\"")
|
||||
|
||||
add_definitions(
|
||||
-DHW_UAVCAN_NAME=${uavcanblid_name}
|
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
|
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
|
||||
)
|
||||
@@ -64,9 +64,6 @@
|
||||
// Hacks for MAVLink RC button input
|
||||
#define ATL_MANTIS_RC_INPUT_HACKS
|
||||
|
||||
// Hacks for MAVLink RC button input
|
||||
#define ATL_MANTIS_RC_INPUT_HACKS
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
|
||||
@@ -4,13 +4,13 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP101XX=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
|
||||
CONFIG_DRIVERS_QSHELL_QURT=y
|
||||
CONFIG_DRIVERS_VOXL2_IO=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
@@ -28,4 +28,5 @@ CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_ORB_COMMUNICATOR=y
|
||||
|
||||
@@ -44,11 +44,10 @@ add_library(drivers_board
|
||||
)
|
||||
|
||||
# Add custom drivers for SLPI
|
||||
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/icm42688p)
|
||||
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/rc_controller)
|
||||
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in)
|
||||
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc)
|
||||
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc)
|
||||
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
|
||||
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
|
||||
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus)
|
||||
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/elrs_led)
|
||||
|
||||
@@ -989,10 +989,10 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
|
||||
|
||||
gps.device_id = device_id.devid;
|
||||
|
||||
gps.lat = hil_gps.lat;
|
||||
gps.lon = hil_gps.lon;
|
||||
gps.alt = hil_gps.alt;
|
||||
gps.alt_ellipsoid = hil_gps.alt;
|
||||
gps.latitude_deg = hil_gps.lat;
|
||||
gps.longitude_deg = hil_gps.lon;
|
||||
gps.altitude_msl_m = hil_gps.alt;
|
||||
gps.altitude_ellipsoid_m = hil_gps.alt;
|
||||
|
||||
gps.s_variance_m_s = 0.25f;
|
||||
gps.c_variance_rad = 0.5f;
|
||||
|
||||
@@ -1,991 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "ICM42688P.hpp"
|
||||
|
||||
bool hitl_mode = false;
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
{
|
||||
return (msb << 8u) | lsb;
|
||||
}
|
||||
|
||||
ICM42688P::ICM42688P(const I2CSPIDriverConfig &config) :
|
||||
// SPI(DRV_IMU_DEVTYPE_ICM42688P, MODULE_NAME, bus, device, spi_mode, bus_frequency),
|
||||
// I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
|
||||
// _drdy_gpio(drdy_gpio)
|
||||
SPI(config),
|
||||
I2CSPIDriver(config),
|
||||
_drdy_gpio(config.drdy_gpio),
|
||||
_px4_accel(get_device_id(), config.rotation),
|
||||
_px4_gyro(get_device_id(), config.rotation)
|
||||
{
|
||||
if (config.drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
}
|
||||
|
||||
if (!hitl_mode) {
|
||||
// _px4_accel = std::make_shared<PX4Accelerometer>(get_device_id(), rotation);
|
||||
// _px4_gyro = std::make_shared<PX4Gyroscope>(get_device_id(), rotation);
|
||||
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
|
||||
// _imu_server_pub.advertise();
|
||||
|
||||
} else {
|
||||
ConfigureSampleRate(0);
|
||||
}
|
||||
}
|
||||
|
||||
ICM42688P::~ICM42688P()
|
||||
{
|
||||
perf_free(_bad_register_perf);
|
||||
perf_free(_bad_transfer_perf);
|
||||
perf_free(_fifo_empty_perf);
|
||||
perf_free(_fifo_overflow_perf);
|
||||
perf_free(_fifo_reset_perf);
|
||||
perf_free(_drdy_missed_perf);
|
||||
|
||||
// if (!hitl_mode){
|
||||
// _imu_server_pub.unadvertise();
|
||||
// }
|
||||
}
|
||||
|
||||
int ICM42688P::init()
|
||||
{
|
||||
int ret = SPI::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
DEVICE_DEBUG("SPI::init failed (%i)", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
return Reset() ? 0 : -1;
|
||||
}
|
||||
|
||||
bool ICM42688P::Reset()
|
||||
{
|
||||
_state = STATE::RESET;
|
||||
DataReadyInterruptDisable();
|
||||
ScheduleClear();
|
||||
ScheduleNow();
|
||||
return true;
|
||||
}
|
||||
|
||||
void ICM42688P::exit_and_cleanup()
|
||||
{
|
||||
DataReadyInterruptDisable();
|
||||
I2CSPIDriverBase::exit_and_cleanup();
|
||||
}
|
||||
|
||||
void ICM42688P::print_status()
|
||||
{
|
||||
I2CSPIDriverBase::print_status();
|
||||
|
||||
PX4_INFO("FIFO empty interval: %d us (%.1f Hz)", _fifo_empty_interval_us, 1e6 / _fifo_empty_interval_us);
|
||||
|
||||
perf_print_counter(_bad_register_perf);
|
||||
perf_print_counter(_bad_transfer_perf);
|
||||
perf_print_counter(_fifo_empty_perf);
|
||||
perf_print_counter(_fifo_overflow_perf);
|
||||
perf_print_counter(_fifo_reset_perf);
|
||||
perf_print_counter(_drdy_missed_perf);
|
||||
}
|
||||
|
||||
int ICM42688P::probe()
|
||||
{
|
||||
for (int i = 0; i < 3; i++) {
|
||||
uint8_t whoami = RegisterRead(Register::BANK_0::WHO_AM_I);
|
||||
|
||||
if (whoami == WHOAMI) {
|
||||
PX4_INFO("ICM42688P::probe successful!");
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
DEVICE_DEBUG("unexpected WHO_AM_I 0x%02x", whoami);
|
||||
|
||||
uint8_t reg_bank_sel = RegisterRead(Register::BANK_0::REG_BANK_SEL);
|
||||
int bank = reg_bank_sel >> 4;
|
||||
|
||||
if (bank >= 1 && bank <= 3) {
|
||||
DEVICE_DEBUG("incorrect register bank for WHO_AM_I REG_BANK_SEL:0x%02x, bank:%d", reg_bank_sel, bank);
|
||||
// force bank selection and retry
|
||||
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0, true);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
void ICM42688P::RunImpl()
|
||||
{
|
||||
PX4_INFO(">>> ICM42688P this: %p", this);
|
||||
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
switch (_state) {
|
||||
case STATE::RESET:
|
||||
// DEVICE_CONFIG: Software reset configuration
|
||||
RegisterWrite(Register::BANK_0::DEVICE_CONFIG, DEVICE_CONFIG_BIT::SOFT_RESET_CONFIG);
|
||||
_reset_timestamp = now;
|
||||
_failure_count = 0;
|
||||
_state = STATE::WAIT_FOR_RESET;
|
||||
ScheduleDelayed(2_ms); // to be safe wait 2 ms for soft reset to be effective
|
||||
break;
|
||||
|
||||
case STATE::WAIT_FOR_RESET:
|
||||
if ((RegisterRead(Register::BANK_0::WHO_AM_I) == WHOAMI)
|
||||
&& (RegisterRead(Register::BANK_0::DEVICE_CONFIG) == 0x00)
|
||||
&& (RegisterRead(Register::BANK_0::INT_STATUS) & INT_STATUS_BIT::RESET_DONE_INT)) {
|
||||
|
||||
_state = STATE::CONFIGURE;
|
||||
ScheduleDelayed(10_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data
|
||||
|
||||
} else {
|
||||
// RESET not complete
|
||||
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
|
||||
PX4_DEBUG("Reset failed, retrying");
|
||||
_state = STATE::RESET;
|
||||
ScheduleDelayed(100_ms);
|
||||
|
||||
} else {
|
||||
PX4_DEBUG("Reset not complete, check again in 10 ms");
|
||||
ScheduleDelayed(10_ms);
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case STATE::CONFIGURE:
|
||||
|
||||
if (Configure()) {
|
||||
|
||||
// Wakeup accel and gyro after configuring registers
|
||||
ScheduleDelayed(1_ms); // add a delay here to be safe
|
||||
RegisterWrite(Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE);
|
||||
ScheduleDelayed(30_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data
|
||||
|
||||
// if configure succeeded then start reading from FIFO
|
||||
_state = STATE::FIFO_READ;
|
||||
|
||||
if (DataReadyInterruptConfigure()) {
|
||||
_data_ready_interrupt_enabled = true;
|
||||
|
||||
// backup schedule as a watchdog timeout
|
||||
ScheduleDelayed(100_ms);
|
||||
|
||||
} else {
|
||||
PX4_ERR("ICM42688P::RunImpl interrupt configuration failed");
|
||||
|
||||
_data_ready_interrupt_enabled = false;
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, _fifo_empty_interval_us);
|
||||
}
|
||||
|
||||
FIFOReset();
|
||||
|
||||
} else {
|
||||
|
||||
PX4_ERR("ICM42688P::RunImpl configuration failed");
|
||||
|
||||
// CONFIGURE not complete
|
||||
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
|
||||
PX4_DEBUG("Configure failed, resetting");
|
||||
_state = STATE::RESET;
|
||||
|
||||
} else {
|
||||
PX4_DEBUG("Configure failed, retrying");
|
||||
}
|
||||
|
||||
ScheduleDelayed(100_ms);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case STATE::FIFO_READ: {
|
||||
#ifndef __PX4_QURT
|
||||
uint32_t samples = 0;
|
||||
|
||||
if (_data_ready_interrupt_enabled) {
|
||||
// scheduled from interrupt if _drdy_fifo_read_samples was set as expected
|
||||
if (_drdy_fifo_read_samples.fetch_and(0) != _fifo_gyro_samples) {
|
||||
perf_count(_drdy_missed_perf);
|
||||
|
||||
} else {
|
||||
samples = _fifo_gyro_samples;
|
||||
}
|
||||
|
||||
// push backup schedule back
|
||||
ScheduleDelayed(_fifo_empty_interval_us * 2);
|
||||
}
|
||||
|
||||
if (samples == 0) {
|
||||
// check current FIFO count
|
||||
const uint16_t fifo_count = FIFOReadCount();
|
||||
|
||||
if (fifo_count >= FIFO::SIZE) {
|
||||
FIFOReset();
|
||||
perf_count(_fifo_overflow_perf);
|
||||
|
||||
} else if (fifo_count == 0) {
|
||||
perf_count(_fifo_empty_perf);
|
||||
|
||||
} else {
|
||||
// FIFO count (size in bytes)
|
||||
samples = (fifo_count / sizeof(FIFO::DATA));
|
||||
|
||||
if (samples > FIFO_MAX_SAMPLES) {
|
||||
// not technically an overflow, but more samples than we expected or can publish
|
||||
FIFOReset();
|
||||
perf_count(_fifo_overflow_perf);
|
||||
samples = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool success = false;
|
||||
|
||||
if (samples >= 1) {
|
||||
if (FIFORead(now, samples)) {
|
||||
success = true;
|
||||
|
||||
if (_failure_count > 0) {
|
||||
_failure_count--;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (!success) {
|
||||
_failure_count++;
|
||||
|
||||
// full reset if things are failing consistently
|
||||
if (_failure_count > 10) {
|
||||
Reset();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// check configuration registers periodically or immediately following any failure
|
||||
if (RegisterCheck(_register_bank0_cfg[_checked_register_bank0])
|
||||
&& RegisterCheck(_register_bank1_cfg[_checked_register_bank1])
|
||||
&& RegisterCheck(_register_bank2_cfg[_checked_register_bank2])
|
||||
) {
|
||||
_last_config_check_timestamp = now;
|
||||
_checked_register_bank0 = (_checked_register_bank0 + 1) % size_register_bank0_cfg;
|
||||
_checked_register_bank1 = (_checked_register_bank1 + 1) % size_register_bank1_cfg;
|
||||
_checked_register_bank2 = (_checked_register_bank2 + 1) % size_register_bank2_cfg;
|
||||
|
||||
} else {
|
||||
// register check failed, force reset
|
||||
perf_count(_bad_register_perf);
|
||||
Reset();
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ICM42688P::ConfigureSampleRate(int sample_rate)
|
||||
{
|
||||
if (sample_rate == 0) {
|
||||
sample_rate = 800; // default to 800 Hz
|
||||
}
|
||||
|
||||
// round down to nearest FIFO sample dt
|
||||
const float min_interval = FIFO_SAMPLE_DT;
|
||||
_fifo_empty_interval_us = math::max(roundf((1e6f / (float)sample_rate) / min_interval) * min_interval, min_interval);
|
||||
|
||||
_fifo_gyro_samples = roundf(math::min((float)_fifo_empty_interval_us / (1e6f / GYRO_RATE), (float)FIFO_MAX_SAMPLES));
|
||||
|
||||
// recompute FIFO empty interval (us) with actual gyro sample limit
|
||||
_fifo_empty_interval_us = _fifo_gyro_samples * (1e6f / GYRO_RATE);
|
||||
|
||||
ConfigureFIFOWatermark(_fifo_gyro_samples);
|
||||
}
|
||||
|
||||
void ICM42688P::ConfigureFIFOWatermark(uint8_t samples)
|
||||
{
|
||||
// FIFO watermark threshold in number of bytes
|
||||
const uint16_t fifo_watermark_threshold = samples * sizeof(FIFO::DATA);
|
||||
|
||||
for (auto &r : _register_bank0_cfg) {
|
||||
if (r.reg == Register::BANK_0::FIFO_CONFIG2) {
|
||||
// FIFO_WM[7:0] FIFO_CONFIG2
|
||||
r.set_bits = fifo_watermark_threshold & 0xFF;
|
||||
|
||||
} else if (r.reg == Register::BANK_0::FIFO_CONFIG3) {
|
||||
// FIFO_WM[11:8] FIFO_CONFIG3
|
||||
r.set_bits = (fifo_watermark_threshold >> 8) & 0x0F;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ICM42688P::SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force)
|
||||
{
|
||||
if (bank != _last_register_bank || force) {
|
||||
// select BANK_0
|
||||
uint8_t cmd_bank_sel[2] {};
|
||||
cmd_bank_sel[0] = static_cast<uint8_t>(Register::BANK_0::REG_BANK_SEL);
|
||||
cmd_bank_sel[1] = bank;
|
||||
transfer(cmd_bank_sel, cmd_bank_sel, sizeof(cmd_bank_sel));
|
||||
|
||||
_last_register_bank = bank;
|
||||
}
|
||||
}
|
||||
|
||||
bool ICM42688P::Configure()
|
||||
{
|
||||
// first set and clear all configured register bits
|
||||
for (const auto ®_cfg : _register_bank0_cfg) {
|
||||
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
|
||||
}
|
||||
|
||||
for (const auto ®_cfg : _register_bank1_cfg) {
|
||||
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
|
||||
}
|
||||
|
||||
for (const auto ®_cfg : _register_bank2_cfg) {
|
||||
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
|
||||
}
|
||||
|
||||
// now check that all are configured
|
||||
bool success = true;
|
||||
|
||||
for (const auto ®_cfg : _register_bank0_cfg) {
|
||||
if (!RegisterCheck(reg_cfg)) {
|
||||
success = false;
|
||||
}
|
||||
}
|
||||
|
||||
for (const auto ®_cfg : _register_bank1_cfg) {
|
||||
if (!RegisterCheck(reg_cfg)) {
|
||||
success = false;
|
||||
}
|
||||
}
|
||||
|
||||
for (const auto ®_cfg : _register_bank2_cfg) {
|
||||
if (!RegisterCheck(reg_cfg)) {
|
||||
success = false;
|
||||
}
|
||||
}
|
||||
|
||||
// // 20-bits data format used
|
||||
// // the only FSR settings that are operational are ±2000dps for gyroscope and ±16g for accelerometer
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.set_range(16.f * CONSTANTS_ONE_G);
|
||||
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f);
|
||||
_px4_gyro.set_range(math::radians(2000.f));
|
||||
_px4_gyro.set_scale(math::radians(1.f / 131.f));
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
static bool interrupt_debug = false;
|
||||
static uint32_t interrupt_debug_count = 0;
|
||||
static const uint32_t interrupt_debug_trigger = 800;
|
||||
static hrt_abstime last_interrupt_time = 0;
|
||||
static hrt_abstime avg_interrupt_delta = 0;
|
||||
static hrt_abstime max_interrupt_delta = 0;
|
||||
static hrt_abstime min_interrupt_delta = 60 * 1000 * 1000;
|
||||
static hrt_abstime cumulative_interrupt_delta = 0;
|
||||
|
||||
int ICM42688P::DataReadyInterruptCallback(int irq, void *context, void *arg)
|
||||
{
|
||||
hrt_abstime current_interrupt_time = hrt_absolute_time();
|
||||
|
||||
if (interrupt_debug) {
|
||||
if (last_interrupt_time) {
|
||||
hrt_abstime interrupt_delta_time = current_interrupt_time - last_interrupt_time;
|
||||
|
||||
if (interrupt_delta_time > max_interrupt_delta) { max_interrupt_delta = interrupt_delta_time; }
|
||||
|
||||
if (interrupt_delta_time < min_interrupt_delta) { min_interrupt_delta = interrupt_delta_time; }
|
||||
|
||||
cumulative_interrupt_delta += interrupt_delta_time;
|
||||
}
|
||||
|
||||
last_interrupt_time = current_interrupt_time;
|
||||
|
||||
interrupt_debug_count++;
|
||||
|
||||
if (interrupt_debug_count == interrupt_debug_trigger) {
|
||||
avg_interrupt_delta = cumulative_interrupt_delta / interrupt_debug_trigger;
|
||||
PX4_INFO(">>> Max: %llu, Min: %llu, Avg: %llu", max_interrupt_delta,
|
||||
min_interrupt_delta, avg_interrupt_delta);
|
||||
interrupt_debug_count = 0;
|
||||
cumulative_interrupt_delta = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static_cast<ICM42688P *>(arg)->DataReady();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void ICM42688P::DataReady()
|
||||
{
|
||||
#ifndef __PX4_QURT
|
||||
uint32_t expected = 0;
|
||||
|
||||
if (_drdy_fifo_read_samples.compare_exchange(&expected, _fifo_gyro_samples)) {
|
||||
ScheduleNow();
|
||||
}
|
||||
|
||||
#else
|
||||
uint16_t fifo_byte_count = FIFOReadCount();
|
||||
|
||||
FIFORead(hrt_absolute_time(), fifo_byte_count / sizeof(FIFO::DATA));
|
||||
#endif
|
||||
}
|
||||
|
||||
bool ICM42688P::DataReadyInterruptConfigure()
|
||||
{
|
||||
if (_drdy_gpio == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Setup data ready on falling edge
|
||||
return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &DataReadyInterruptCallback, this) == 0;
|
||||
}
|
||||
|
||||
bool ICM42688P::DataReadyInterruptDisable()
|
||||
{
|
||||
if (_drdy_gpio == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
bool ICM42688P::RegisterCheck(const T ®_cfg)
|
||||
{
|
||||
bool success = true;
|
||||
|
||||
const uint8_t reg_value = RegisterRead(reg_cfg.reg);
|
||||
|
||||
if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) {
|
||||
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits);
|
||||
success = false;
|
||||
}
|
||||
|
||||
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) {
|
||||
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits);
|
||||
success = false;
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
uint8_t ICM42688P::RegisterRead(T reg)
|
||||
{
|
||||
uint8_t cmd[2] {};
|
||||
cmd[0] = static_cast<uint8_t>(reg) | DIR_READ;
|
||||
SelectRegisterBank(reg);
|
||||
transfer(cmd, cmd, sizeof(cmd));
|
||||
return cmd[1];
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void ICM42688P::RegisterWrite(T reg, uint8_t value)
|
||||
{
|
||||
uint8_t cmd[2] { (uint8_t)reg, value };
|
||||
SelectRegisterBank(reg);
|
||||
transfer(cmd, cmd, sizeof(cmd));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
void ICM42688P::RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits)
|
||||
{
|
||||
const uint8_t orig_val = RegisterRead(reg);
|
||||
|
||||
uint8_t val = (orig_val & ~clearbits) | setbits;
|
||||
|
||||
if (orig_val != val) {
|
||||
RegisterWrite(reg, val);
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t ICM42688P::FIFOReadCount()
|
||||
{
|
||||
// read FIFO count
|
||||
uint8_t fifo_count_buf[3] {};
|
||||
fifo_count_buf[0] = static_cast<uint8_t>(Register::BANK_0::FIFO_COUNTH) | DIR_READ;
|
||||
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0);
|
||||
|
||||
if (transfer(fifo_count_buf, fifo_count_buf, sizeof(fifo_count_buf)) != PX4_OK) {
|
||||
perf_count(_bad_transfer_perf);
|
||||
return 0;
|
||||
}
|
||||
|
||||
return combine(fifo_count_buf[1], fifo_count_buf[2]);
|
||||
}
|
||||
|
||||
// static uint32_t debug_decimator = 0;
|
||||
// static hrt_abstime last_sample_time = 0;
|
||||
// static bool imu_debug = true;
|
||||
|
||||
bool ICM42688P::FIFORead(const hrt_abstime ×tamp_sample, uint16_t samples)
|
||||
{
|
||||
FIFOTransferBuffer buffer{};
|
||||
const size_t max_transfer_size = 10 * sizeof(FIFO::DATA) + 4;
|
||||
const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 4, max_transfer_size);
|
||||
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0);
|
||||
|
||||
if (transfer((uint8_t *)&buffer, (uint8_t *)&buffer, transfer_size) != PX4_OK) {
|
||||
perf_count(_bad_transfer_perf);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (buffer.INT_STATUS & INT_STATUS_BIT::FIFO_FULL_INT) {
|
||||
perf_count(_fifo_overflow_perf);
|
||||
FIFOReset();
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint16_t fifo_count_bytes = combine(buffer.FIFO_COUNTH, buffer.FIFO_COUNTL);
|
||||
|
||||
if (fifo_count_bytes >= FIFO::SIZE) {
|
||||
perf_count(_fifo_overflow_perf);
|
||||
FIFOReset();
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint16_t fifo_count_samples = fifo_count_bytes / sizeof(FIFO::DATA);
|
||||
|
||||
if (fifo_count_samples == 0) {
|
||||
perf_count(_fifo_empty_perf);
|
||||
return false;
|
||||
}
|
||||
|
||||
// check FIFO header in every sample
|
||||
uint16_t valid_samples = 0;
|
||||
|
||||
// for (int i = 0; i < math::min(samples, fifo_count_samples); i++) {
|
||||
for (int i = 0; i < math::min(samples, (uint16_t) 10); i++) {
|
||||
bool valid = true;
|
||||
|
||||
// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx
|
||||
const uint8_t FIFO_HEADER = buffer.f[i].FIFO_Header;
|
||||
|
||||
if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_MSG) {
|
||||
// FIFO sample empty if HEADER_MSG set
|
||||
valid = false;
|
||||
|
||||
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ACCEL)) {
|
||||
// accel bit not set
|
||||
valid = false;
|
||||
|
||||
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_GYRO)) {
|
||||
// gyro bit not set
|
||||
valid = false;
|
||||
|
||||
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_20)) {
|
||||
// Packet does not contain a new and valid extended 20-bit data
|
||||
valid = false;
|
||||
|
||||
} else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_ACCEL) {
|
||||
// accel ODR changed
|
||||
valid = false;
|
||||
|
||||
} else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_GYRO) {
|
||||
// gyro ODR changed
|
||||
valid = false;
|
||||
}
|
||||
|
||||
if (valid) {
|
||||
valid_samples++;
|
||||
|
||||
} else {
|
||||
perf_count(_bad_transfer_perf);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// if (imu_debug) {
|
||||
// debug_decimator++;
|
||||
// if (debug_decimator == 801) {
|
||||
// debug_decimator = 0;
|
||||
// PX4_INFO("Initial: %u Next: %u Valid: %u Delta: %llu", samples, fifo_count_samples, valid_samples, timestamp_sample - last_sample_time);
|
||||
// }
|
||||
// last_sample_time = timestamp_sample;
|
||||
// }
|
||||
|
||||
if (valid_samples > 0) {
|
||||
if (ProcessTemperature(buffer.f, valid_samples)) {
|
||||
ProcessGyro(timestamp_sample, buffer.f, valid_samples);
|
||||
ProcessAccel(timestamp_sample, buffer.f, valid_samples);
|
||||
ProcessIMU(timestamp_sample, buffer.f, valid_samples);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void ICM42688P::FIFOReset()
|
||||
{
|
||||
perf_count(_fifo_reset_perf);
|
||||
|
||||
// SIGNAL_PATH_RESET: FIFO flush
|
||||
RegisterSetBits(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::FIFO_FLUSH);
|
||||
|
||||
// reset while FIFO is disabled
|
||||
_drdy_fifo_read_samples.store(0);
|
||||
}
|
||||
|
||||
static constexpr int32_t reassemble_20bit(const uint32_t a, const uint32_t b, const uint32_t c)
|
||||
{
|
||||
// 0xXXXAABBC
|
||||
uint32_t high = ((a << 12) & 0x000FF000);
|
||||
uint32_t low = ((b << 4) & 0x00000FF0);
|
||||
uint32_t lowest = (c & 0x0000000F);
|
||||
|
||||
uint32_t x = high | low | lowest;
|
||||
|
||||
if (a & Bit7) {
|
||||
// sign extend
|
||||
x |= 0xFFF00000u;
|
||||
}
|
||||
|
||||
return static_cast<int32_t>(x);
|
||||
}
|
||||
|
||||
void ICM42688P::ProcessIMU(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
|
||||
{
|
||||
float accel_x = 0.0, accel_y = 0.0, accel_z = 0.0;
|
||||
float gyro_x = 0.0, gyro_y = 0.0, gyro_z = 0.0;
|
||||
|
||||
for (int i = 0; i < samples; i++) {
|
||||
_imu_server_decimator++;
|
||||
|
||||
if (_imu_server_decimator == 8) {
|
||||
_imu_server_decimator = 0;
|
||||
// 20 bit hires mode
|
||||
|
||||
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
|
||||
// Accel data is 18 bit
|
||||
int32_t temp_accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0,
|
||||
fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4);
|
||||
int32_t temp_accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0,
|
||||
fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4);
|
||||
int32_t temp_accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0,
|
||||
fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4);
|
||||
|
||||
// Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte)
|
||||
int32_t temp_gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0,
|
||||
fifo[i].Ext_Accel_X_Gyro_X & 0x0F);
|
||||
int32_t temp_gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0,
|
||||
fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F);
|
||||
int32_t temp_gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0,
|
||||
fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F);
|
||||
|
||||
// accel samples invalid if -524288
|
||||
if (temp_accel_x != -524288 && temp_accel_y != -524288 && temp_accel_z != -524288) {
|
||||
// shift accel by 2 (2 least significant bits are always 0)
|
||||
accel_x = (float) temp_accel_x / 4.f;
|
||||
accel_y = (float) temp_accel_y / 4.f;
|
||||
accel_z = (float) temp_accel_z / 4.f;
|
||||
|
||||
// shift gyro by 1 (least significant bit is always 0)
|
||||
gyro_x = (float) temp_gyro_x / 2.f;
|
||||
gyro_y = (float) temp_gyro_y / 2.f;
|
||||
gyro_z = (float) temp_gyro_z / 2.f;
|
||||
|
||||
// correct frame for publication
|
||||
// sensor's frame is +x forward, +y left, +z up
|
||||
// flip y & z to publish right handed with z down (x forward, y right, z down)
|
||||
accel_y = -accel_y;
|
||||
accel_z = -accel_z;
|
||||
gyro_y = -gyro_y;
|
||||
gyro_z = -gyro_z;
|
||||
|
||||
// Scale everything appropriately
|
||||
float accel_scale_factor = (CONSTANTS_ONE_G / 8192.f);
|
||||
accel_x *= accel_scale_factor;
|
||||
accel_y *= accel_scale_factor;
|
||||
accel_z *= accel_scale_factor;
|
||||
|
||||
float gyro_scale_factor = math::radians(1.f / 131.f);
|
||||
gyro_x *= gyro_scale_factor;
|
||||
gyro_y *= gyro_scale_factor;
|
||||
gyro_z *= gyro_scale_factor;
|
||||
|
||||
// Store the data in our array
|
||||
_imu_server_data.accel_x[_imu_server_index] = accel_x;
|
||||
_imu_server_data.accel_y[_imu_server_index] = accel_y;
|
||||
_imu_server_data.accel_z[_imu_server_index] = accel_z;
|
||||
_imu_server_data.gyro_x[_imu_server_index] = gyro_x;
|
||||
_imu_server_data.gyro_y[_imu_server_index] = gyro_y;
|
||||
_imu_server_data.gyro_z[_imu_server_index] = gyro_z;
|
||||
_imu_server_data.ts[_imu_server_index] = timestamp_sample - (125 * (samples - 1 - i));
|
||||
_imu_server_index++;
|
||||
|
||||
// If array is full, publish the data
|
||||
if (_imu_server_index == 10) {
|
||||
_imu_server_index = 0;
|
||||
_imu_server_data.timestamp = hrt_absolute_time();
|
||||
_imu_server_data.temperature = 0; // Not used right now
|
||||
_imu_server_pub.publish(_imu_server_data);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ICM42688P::ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
|
||||
{
|
||||
sensor_accel_fifo_s accel{};
|
||||
accel.timestamp_sample = timestamp_sample;
|
||||
accel.samples = 0;
|
||||
accel.dt = FIFO_SAMPLE_DT;
|
||||
|
||||
// 18-bits of accelerometer data
|
||||
bool scale_20bit = false;
|
||||
|
||||
// first pass
|
||||
for (int i = 0; i < samples; i++) {
|
||||
// 20 bit hires mode
|
||||
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
|
||||
// Accel data is 18 bit ()
|
||||
int32_t accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0,
|
||||
fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4);
|
||||
int32_t accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0,
|
||||
fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4);
|
||||
int32_t accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0,
|
||||
fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4);
|
||||
|
||||
// sample invalid if -524288
|
||||
if (accel_x != -524288 && accel_y != -524288 && accel_z != -524288) {
|
||||
// check if any values are going to exceed int16 limits
|
||||
static constexpr int16_t max_accel = INT16_MAX;
|
||||
static constexpr int16_t min_accel = INT16_MIN;
|
||||
|
||||
if (accel_x >= max_accel || accel_x <= min_accel) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
if (accel_y >= max_accel || accel_y <= min_accel) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
if (accel_z >= max_accel || accel_z <= min_accel) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
// shift by 2 (2 least significant bits are always 0)
|
||||
accel.x[accel.samples] = accel_x / 4;
|
||||
accel.y[accel.samples] = accel_y / 4;
|
||||
accel.z[accel.samples] = accel_z / 4;
|
||||
accel.samples++;
|
||||
}
|
||||
}
|
||||
|
||||
if (!scale_20bit) {
|
||||
// if highres enabled accel data is always 8192 LSB/g
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f);
|
||||
}
|
||||
|
||||
} else {
|
||||
// 20 bit data scaled to 16 bit (2^4)
|
||||
for (int i = 0; i < samples; i++) {
|
||||
// 20 bit hires mode
|
||||
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
|
||||
// Accel data is 18 bit ()
|
||||
int16_t accel_x = combine(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0);
|
||||
int16_t accel_y = combine(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0);
|
||||
int16_t accel_z = combine(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0);
|
||||
|
||||
accel.x[i] = accel_x;
|
||||
accel.y[i] = accel_y;
|
||||
accel.z[i] = accel_z;
|
||||
}
|
||||
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f);
|
||||
}
|
||||
}
|
||||
|
||||
// correct frame for publication
|
||||
for (int i = 0; i < accel.samples; i++) {
|
||||
// sensor's frame is +x forward, +y left, +z up
|
||||
// flip y & z to publish right handed with z down (x forward, y right, z down)
|
||||
accel.x[i] = accel.x[i];
|
||||
accel.y[i] = (accel.y[i] == INT16_MIN) ? INT16_MAX : -accel.y[i];
|
||||
accel.z[i] = (accel.z[i] == INT16_MIN) ? INT16_MAX : -accel.z[i];
|
||||
}
|
||||
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) +
|
||||
perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf));
|
||||
}
|
||||
|
||||
if (accel.samples > 0) {
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.updateFIFO(accel);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ICM42688P::ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
|
||||
{
|
||||
sensor_gyro_fifo_s gyro{};
|
||||
gyro.timestamp_sample = timestamp_sample;
|
||||
gyro.samples = 0;
|
||||
gyro.dt = FIFO_SAMPLE_DT;
|
||||
|
||||
// 20-bits of gyroscope data
|
||||
bool scale_20bit = false;
|
||||
|
||||
// first pass
|
||||
for (int i = 0; i < samples; i++) {
|
||||
// 20 bit hires mode
|
||||
// Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte)
|
||||
int32_t gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0, fifo[i].Ext_Accel_X_Gyro_X & 0x0F);
|
||||
int32_t gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0, fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F);
|
||||
int32_t gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0, fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F);
|
||||
|
||||
// check if any values are going to exceed int16 limits
|
||||
static constexpr int16_t max_gyro = INT16_MAX;
|
||||
static constexpr int16_t min_gyro = INT16_MIN;
|
||||
|
||||
if (gyro_x >= max_gyro || gyro_x <= min_gyro) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
if (gyro_y >= max_gyro || gyro_y <= min_gyro) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
if (gyro_z >= max_gyro || gyro_z <= min_gyro) {
|
||||
scale_20bit = true;
|
||||
}
|
||||
|
||||
gyro.x[gyro.samples] = gyro_x / 2;
|
||||
gyro.y[gyro.samples] = gyro_y / 2;
|
||||
gyro.z[gyro.samples] = gyro_z / 2;
|
||||
gyro.samples++;
|
||||
}
|
||||
|
||||
if (!scale_20bit) {
|
||||
// if highres enabled gyro data is always 131 LSB/dps
|
||||
if (!hitl_mode) {
|
||||
_px4_gyro.set_scale(math::radians(1.f / 131.f));
|
||||
}
|
||||
|
||||
} else {
|
||||
// 20 bit data scaled to 16 bit (2^4)
|
||||
for (int i = 0; i < samples; i++) {
|
||||
gyro.x[i] = combine(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0);
|
||||
gyro.y[i] = combine(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0);
|
||||
gyro.z[i] = combine(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0);
|
||||
}
|
||||
|
||||
if (!hitl_mode) {
|
||||
_px4_gyro.set_scale(math::radians(2000.f / 32768.f));
|
||||
}
|
||||
}
|
||||
|
||||
// correct frame for publication
|
||||
for (int i = 0; i < gyro.samples; i++) {
|
||||
// sensor's frame is +x forward, +y left, +z up
|
||||
// flip y & z to publish right handed with z down (x forward, y right, z down)
|
||||
gyro.x[i] = gyro.x[i];
|
||||
gyro.y[i] = (gyro.y[i] == INT16_MIN) ? INT16_MAX : -gyro.y[i];
|
||||
gyro.z[i] = (gyro.z[i] == INT16_MIN) ? INT16_MAX : -gyro.z[i];
|
||||
}
|
||||
|
||||
if (!hitl_mode) {
|
||||
_px4_gyro.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) +
|
||||
perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf));
|
||||
}
|
||||
|
||||
if (gyro.samples > 0) {
|
||||
if (!hitl_mode) {
|
||||
_px4_gyro.updateFIFO(gyro);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool ICM42688P::ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples)
|
||||
{
|
||||
int16_t temperature[FIFO_MAX_SAMPLES];
|
||||
float temperature_sum{0};
|
||||
|
||||
int valid_samples = 0;
|
||||
|
||||
for (int i = 0; i < samples; i++) {
|
||||
const int16_t t = combine(fifo[i].TEMP_DATA1, fifo[i].TEMP_DATA0);
|
||||
|
||||
// sample invalid if -32768
|
||||
if (t != -32768) {
|
||||
temperature_sum += t;
|
||||
temperature[valid_samples] = t;
|
||||
valid_samples++;
|
||||
}
|
||||
}
|
||||
|
||||
if (valid_samples > 0) {
|
||||
const float temperature_avg = temperature_sum / valid_samples;
|
||||
|
||||
for (int i = 0; i < valid_samples; i++) {
|
||||
// temperature changing wildly is an indication of a transfer error
|
||||
if (fabsf(temperature[i] - temperature_avg) > 1000) {
|
||||
perf_count(_bad_transfer_perf);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// use average temperature reading
|
||||
const float TEMP_degC = (temperature_avg / TEMPERATURE_SENSITIVITY) + TEMPERATURE_OFFSET;
|
||||
|
||||
if (PX4_ISFINITE(TEMP_degC)) {
|
||||
if (!hitl_mode) {
|
||||
_px4_accel.set_temperature(TEMP_degC);
|
||||
_px4_gyro.set_temperature(TEMP_degC);
|
||||
return true;
|
||||
}
|
||||
|
||||
} else {
|
||||
perf_count(_bad_transfer_perf);
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
@@ -1,235 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file ICM42688P.hpp
|
||||
*
|
||||
* Driver for the Invensense ICM42688P connected via SPI.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "InvenSense_ICM42688P_registers.hpp"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
|
||||
#include <lib/drivers/device/spi.h>
|
||||
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
|
||||
#include <lib/geo/geo.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_platform_common/atomic.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <uORB/topics/imu_server.h>
|
||||
#include <uORB/topics/sensor_accel_fifo.h>
|
||||
#include <uORB/topics/sensor_gyro_fifo.h>
|
||||
#include <memory>
|
||||
|
||||
using namespace InvenSense_ICM42688P;
|
||||
|
||||
extern bool hitl_mode;
|
||||
|
||||
class ICM42688P : public device::SPI, public I2CSPIDriver<ICM42688P>
|
||||
{
|
||||
public:
|
||||
// ICM42688P(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
|
||||
// spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio);
|
||||
ICM42688P(const I2CSPIDriverConfig &config);
|
||||
~ICM42688P() override;
|
||||
|
||||
// static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
// int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
int init() override;
|
||||
void print_status() override;
|
||||
|
||||
private:
|
||||
void exit_and_cleanup() override;
|
||||
|
||||
// Sensor Configuration
|
||||
static constexpr float IMU_ODR{8000.f}; // 8kHz accel & gyro ODR configured
|
||||
static constexpr float FIFO_SAMPLE_DT{1e6f / IMU_ODR};
|
||||
static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT};
|
||||
static constexpr float ACCEL_RATE{1e6f / FIFO_SAMPLE_DT};
|
||||
|
||||
// maximum FIFO samples per transfer is limited to the size of sensor_accel_fifo/sensor_gyro_fifo
|
||||
// static constexpr uint32_t FIFO_MAX_SAMPLES{math::min(math::min(FIFO::SIZE / sizeof(FIFO::DATA), sizeof(sensor_gyro_fifo_s::x) / sizeof(sensor_gyro_fifo_s::x[0])), sizeof(sensor_accel_fifo_s::x) / sizeof(sensor_accel_fifo_s::x[0]) * (int)(GYRO_RATE / ACCEL_RATE))};
|
||||
static constexpr uint32_t FIFO_MAX_SAMPLES{10};
|
||||
|
||||
// Transfer data
|
||||
struct FIFOTransferBuffer {
|
||||
uint8_t cmd{static_cast<uint8_t>(Register::BANK_0::INT_STATUS) | DIR_READ};
|
||||
uint8_t INT_STATUS{0};
|
||||
uint8_t FIFO_COUNTH{0};
|
||||
uint8_t FIFO_COUNTL{0};
|
||||
FIFO::DATA f[FIFO_MAX_SAMPLES] {};
|
||||
};
|
||||
// ensure no struct padding
|
||||
static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA)),
|
||||
"Invalid FIFOTransferBuffer size");
|
||||
|
||||
struct register_bank0_config_t {
|
||||
Register::BANK_0 reg;
|
||||
uint8_t set_bits{0};
|
||||
uint8_t clear_bits{0};
|
||||
};
|
||||
|
||||
struct register_bank1_config_t {
|
||||
Register::BANK_1 reg;
|
||||
uint8_t set_bits{0};
|
||||
uint8_t clear_bits{0};
|
||||
};
|
||||
|
||||
struct register_bank2_config_t {
|
||||
Register::BANK_2 reg;
|
||||
uint8_t set_bits{0};
|
||||
uint8_t clear_bits{0};
|
||||
};
|
||||
|
||||
int probe() override;
|
||||
|
||||
bool Reset();
|
||||
|
||||
bool Configure();
|
||||
void ConfigureSampleRate(int sample_rate);
|
||||
void ConfigureFIFOWatermark(uint8_t samples);
|
||||
|
||||
void SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force = false);
|
||||
void SelectRegisterBank(Register::BANK_0 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0); }
|
||||
void SelectRegisterBank(Register::BANK_1 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_1); }
|
||||
void SelectRegisterBank(Register::BANK_2 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_2); }
|
||||
|
||||
static int DataReadyInterruptCallback(int irq, void *context, void *arg);
|
||||
void DataReady();
|
||||
bool DataReadyInterruptConfigure();
|
||||
bool DataReadyInterruptDisable();
|
||||
|
||||
template <typename T> bool RegisterCheck(const T ®_cfg);
|
||||
template <typename T> uint8_t RegisterRead(T reg);
|
||||
template <typename T> void RegisterWrite(T reg, uint8_t value);
|
||||
template <typename T> void RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits);
|
||||
template <typename T> void RegisterSetBits(T reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); }
|
||||
template <typename T> void RegisterClearBits(T reg, uint8_t clearbits) { RegisterSetAndClearBits(reg, 0, clearbits); }
|
||||
|
||||
uint16_t FIFOReadCount();
|
||||
bool FIFORead(const hrt_abstime ×tamp_sample, uint16_t samples);
|
||||
void FIFOReset();
|
||||
|
||||
void ProcessIMU(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
|
||||
void ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
|
||||
void ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
|
||||
bool ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples);
|
||||
|
||||
const spi_drdy_gpio_t _drdy_gpio;
|
||||
|
||||
// std::shared_ptr<PX4Accelerometer> _px4_accel;
|
||||
// std::shared_ptr<PX4Gyroscope> _px4_gyro;
|
||||
PX4Accelerometer _px4_accel;
|
||||
PX4Gyroscope _px4_gyro;
|
||||
|
||||
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
|
||||
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
|
||||
perf_counter_t _fifo_empty_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO empty")};
|
||||
perf_counter_t _fifo_overflow_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO overflow")};
|
||||
perf_counter_t _fifo_reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO reset")};
|
||||
perf_counter_t _drdy_missed_perf{nullptr};
|
||||
|
||||
hrt_abstime _reset_timestamp{0};
|
||||
hrt_abstime _last_config_check_timestamp{0};
|
||||
hrt_abstime _temperature_update_timestamp{0};
|
||||
int _failure_count{0};
|
||||
|
||||
enum REG_BANK_SEL_BIT _last_register_bank {REG_BANK_SEL_BIT::USER_BANK_0};
|
||||
|
||||
px4::atomic<uint32_t> _drdy_fifo_read_samples{0};
|
||||
bool _data_ready_interrupt_enabled{false};
|
||||
|
||||
enum class STATE : uint8_t {
|
||||
RESET,
|
||||
WAIT_FOR_RESET,
|
||||
CONFIGURE,
|
||||
FIFO_READ,
|
||||
} _state{STATE::RESET};
|
||||
|
||||
uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval
|
||||
uint32_t _fifo_gyro_samples{static_cast<uint32_t>(_fifo_empty_interval_us / (1000000 / GYRO_RATE))};
|
||||
|
||||
uint8_t _checked_register_bank0{0};
|
||||
static constexpr uint8_t size_register_bank0_cfg{12};
|
||||
register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] {
|
||||
// Register | Set bits, Clear bits
|
||||
{ Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY },
|
||||
{ Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 },
|
||||
{ Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_FS_SEL_2000_DPS | GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_SET, GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_CLEAR },
|
||||
{ Register::BANK_0::ACCEL_CONFIG0, ACCEL_CONFIG0_BIT::ACCEL_FS_SEL_16G | ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_SET, ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_CLEAR },
|
||||
{ Register::BANK_0::GYRO_CONFIG1, 0, GYRO_CONFIG1_BIT::GYRO_UI_FILT_ORD },
|
||||
{ Register::BANK_0::GYRO_ACCEL_CONFIG0, 0, GYRO_ACCEL_CONFIG0_BIT::ACCEL_UI_FILT_BW | GYRO_ACCEL_CONFIG0_BIT::GYRO_UI_FILT_BW },
|
||||
{ Register::BANK_0::ACCEL_CONFIG1, 0, ACCEL_CONFIG1_BIT::ACCEL_UI_FILT_ORD },
|
||||
{ Register::BANK_0::FIFO_CONFIG1, FIFO_CONFIG1_BIT::FIFO_WM_GT_TH | FIFO_CONFIG1_BIT::FIFO_HIRES_EN | FIFO_CONFIG1_BIT::FIFO_TEMP_EN | FIFO_CONFIG1_BIT::FIFO_GYRO_EN | FIFO_CONFIG1_BIT::FIFO_ACCEL_EN, 0 },
|
||||
{ Register::BANK_0::FIFO_CONFIG2, 0, 0 }, // FIFO_WM[7:0] set at runtime
|
||||
{ Register::BANK_0::FIFO_CONFIG3, 0, 0 }, // FIFO_WM[11:8] set at runtime
|
||||
{ Register::BANK_0::INT_CONFIG0, INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ, 0 },
|
||||
{ Register::BANK_0::INT_SOURCE0, INT_SOURCE0_BIT::FIFO_THS_INT1_EN, 0 },
|
||||
};
|
||||
|
||||
uint8_t _checked_register_bank1{0};
|
||||
static constexpr uint8_t size_register_bank1_cfg{4};
|
||||
register_bank1_config_t _register_bank1_cfg[size_register_bank1_cfg] {
|
||||
// Register | Set bits, Clear bits
|
||||
{ Register::BANK_1::GYRO_CONFIG_STATIC2, 0, GYRO_CONFIG_STATIC2_BIT::GYRO_NF_DIS | GYRO_CONFIG_STATIC2_BIT::GYRO_AAF_DIS },
|
||||
{ Register::BANK_1::GYRO_CONFIG_STATIC3, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_SET, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_CLEAR},
|
||||
{ Register::BANK_1::GYRO_CONFIG_STATIC4, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LOW_SET, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LOW_CLEAR},
|
||||
{ Register::BANK_1::GYRO_CONFIG_STATIC5, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_SET | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_HIGH_SET, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_CLEAR | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_HIGH_CLEAR},
|
||||
};
|
||||
|
||||
uint8_t _checked_register_bank2{0};
|
||||
static constexpr uint8_t size_register_bank2_cfg{3};
|
||||
register_bank2_config_t _register_bank2_cfg[size_register_bank2_cfg] {
|
||||
// Register | Set bits, Clear bits
|
||||
{ Register::BANK_2::ACCEL_CONFIG_STATIC2, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_SET, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_CLEAR | ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DIS },
|
||||
{ Register::BANK_2::ACCEL_CONFIG_STATIC3, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LOW_SET, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LOW_CLEAR },
|
||||
{ Register::BANK_2::ACCEL_CONFIG_STATIC4, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_SET | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_HIGH_SET, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_CLEAR | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_HIGH_CLEAR },
|
||||
};
|
||||
|
||||
uint32_t _temperature_samples{0};
|
||||
|
||||
// Support for the IMU server
|
||||
uint32_t _imu_server_index{0};
|
||||
uint32_t _imu_server_decimator{0};
|
||||
imu_server_s _imu_server_data;
|
||||
uORB::Publication<imu_server_s> _imu_server_pub{ORB_ID(imu_server)};
|
||||
|
||||
};
|
||||
@@ -1,430 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file InvenSense_ICM42688P_registers.hpp
|
||||
*
|
||||
* Invensense ICM-42688-P registers.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace InvenSense_ICM42688P
|
||||
{
|
||||
// TODO: move to a central header
|
||||
static constexpr uint8_t Bit0 = (1 << 0);
|
||||
static constexpr uint8_t Bit1 = (1 << 1);
|
||||
static constexpr uint8_t Bit2 = (1 << 2);
|
||||
static constexpr uint8_t Bit3 = (1 << 3);
|
||||
static constexpr uint8_t Bit4 = (1 << 4);
|
||||
static constexpr uint8_t Bit5 = (1 << 5);
|
||||
static constexpr uint8_t Bit6 = (1 << 6);
|
||||
static constexpr uint8_t Bit7 = (1 << 7);
|
||||
|
||||
static constexpr uint32_t SPI_SPEED = 24 * 1000 * 1000; // 24 MHz SPI
|
||||
static constexpr uint8_t DIR_READ = 0x80;
|
||||
|
||||
static constexpr uint8_t WHOAMI = 0x47;
|
||||
|
||||
static constexpr float TEMPERATURE_SENSITIVITY = 132.48f; // LSB/C
|
||||
static constexpr float TEMPERATURE_OFFSET = 25.f; // C
|
||||
|
||||
namespace Register
|
||||
{
|
||||
|
||||
enum class BANK_0 : uint8_t {
|
||||
DEVICE_CONFIG = 0x11,
|
||||
|
||||
INT_CONFIG = 0x14,
|
||||
|
||||
FIFO_CONFIG = 0x16,
|
||||
|
||||
TEMP_DATA1 = 0x1D,
|
||||
TEMP_DATA0 = 0x1E,
|
||||
|
||||
INT_STATUS = 0x2D,
|
||||
FIFO_COUNTH = 0x2E,
|
||||
FIFO_COUNTL = 0x2F,
|
||||
FIFO_DATA = 0x30,
|
||||
|
||||
SIGNAL_PATH_RESET = 0x4B,
|
||||
INTF_CONFIG0 = 0x4C,
|
||||
INTF_CONFIG1 = 0x4D,
|
||||
PWR_MGMT0 = 0x4E,
|
||||
GYRO_CONFIG0 = 0x4F,
|
||||
ACCEL_CONFIG0 = 0x50,
|
||||
GYRO_CONFIG1 = 0x51,
|
||||
GYRO_ACCEL_CONFIG0 = 0x52,
|
||||
ACCEL_CONFIG1 = 0x53,
|
||||
|
||||
FIFO_CONFIG1 = 0x5F,
|
||||
FIFO_CONFIG2 = 0x60,
|
||||
FIFO_CONFIG3 = 0x61,
|
||||
|
||||
INT_CONFIG0 = 0x63,
|
||||
|
||||
INT_SOURCE0 = 0x65,
|
||||
|
||||
SELF_TEST_CONFIG = 0x70,
|
||||
|
||||
WHO_AM_I = 0x75,
|
||||
REG_BANK_SEL = 0x76,
|
||||
};
|
||||
|
||||
enum class BANK_1 : uint8_t {
|
||||
GYRO_CONFIG_STATIC2 = 0x0B,
|
||||
GYRO_CONFIG_STATIC3 = 0x0C,
|
||||
GYRO_CONFIG_STATIC4 = 0x0D,
|
||||
GYRO_CONFIG_STATIC5 = 0x0E,
|
||||
INTF_CONFIG5 = 0x7B,
|
||||
};
|
||||
enum class BANK_2 : uint8_t {
|
||||
ACCEL_CONFIG_STATIC2 = 0x03,
|
||||
ACCEL_CONFIG_STATIC3 = 0x04,
|
||||
ACCEL_CONFIG_STATIC4 = 0x05,
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
//---------------- BANK0 Register bits
|
||||
|
||||
// DEVICE_CONFIG
|
||||
enum DEVICE_CONFIG_BIT : uint8_t {
|
||||
SOFT_RESET_CONFIG = Bit0, //
|
||||
};
|
||||
|
||||
// INT_CONFIG
|
||||
enum INT_CONFIG_BIT : uint8_t {
|
||||
INT1_MODE = Bit2,
|
||||
INT1_DRIVE_CIRCUIT = Bit1,
|
||||
INT1_POLARITY = Bit0,
|
||||
};
|
||||
|
||||
// FIFO_CONFIG
|
||||
enum FIFO_CONFIG_BIT : uint8_t {
|
||||
// 7:6 FIFO_MODE
|
||||
FIFO_MODE_STOP_ON_FULL = Bit7 | Bit6, // 11: STOP-on-FULL Mode
|
||||
};
|
||||
|
||||
// INT_STATUS
|
||||
enum INT_STATUS_BIT : uint8_t {
|
||||
RESET_DONE_INT = Bit4,
|
||||
DATA_RDY_INT = Bit3,
|
||||
FIFO_THS_INT = Bit2,
|
||||
FIFO_FULL_INT = Bit1,
|
||||
};
|
||||
|
||||
// SIGNAL_PATH_RESET
|
||||
enum SIGNAL_PATH_RESET_BIT : uint8_t {
|
||||
ABORT_AND_RESET = Bit3,
|
||||
FIFO_FLUSH = Bit1,
|
||||
};
|
||||
|
||||
// PWR_MGMT0
|
||||
enum PWR_MGMT0_BIT : uint8_t {
|
||||
GYRO_MODE_LOW_NOISE = Bit3 | Bit2, // 11: Places gyroscope in Low Noise (LN) Mode
|
||||
ACCEL_MODE_LOW_NOISE = Bit1 | Bit0, // 11: Places accelerometer in Low Noise (LN) Mode
|
||||
};
|
||||
|
||||
// GYRO_CONFIG0
|
||||
enum GYRO_CONFIG0_BIT : uint8_t {
|
||||
// 7:5 GYRO_FS_SEL
|
||||
GYRO_FS_SEL_2000_DPS = 0, // 0b000 = ±2000dps (default)
|
||||
GYRO_FS_SEL_1000_DPS = Bit5,
|
||||
GYRO_FS_SEL_500_DPS = Bit6,
|
||||
GYRO_FS_SEL_250_DPS = Bit6 | Bit5,
|
||||
GYRO_FS_SEL_125_DPS = Bit7,
|
||||
|
||||
|
||||
// 3:0 GYRO_ODR
|
||||
// 0001: 32kHz
|
||||
GYRO_ODR_32KHZ_SET = Bit0,
|
||||
GYRO_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0,
|
||||
// 0010: 16kHz
|
||||
GYRO_ODR_16KHZ_SET = Bit1,
|
||||
GYRO_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0,
|
||||
// 0011: 8kHz
|
||||
GYRO_ODR_8KHZ_SET = Bit1 | Bit0,
|
||||
GYRO_ODR_8KHZ_CLEAR = Bit3 | Bit2,
|
||||
// 0110: 1kHz (default)
|
||||
GYRO_ODR_1KHZ_SET = Bit2 | Bit1,
|
||||
GYRO_ODR_1KHZ_CLEAR = Bit3 | Bit0,
|
||||
};
|
||||
|
||||
// ACCEL_CONFIG0
|
||||
enum ACCEL_CONFIG0_BIT : uint8_t {
|
||||
// 7:5 ACCEL_FS_SEL
|
||||
ACCEL_FS_SEL_16G = 0, // 000: ±16g (default)
|
||||
ACCEL_FS_SEL_8G = Bit5,
|
||||
ACCEL_FS_SEL_4G = Bit6,
|
||||
ACCEL_FS_SEL_2G = Bit6 | Bit5,
|
||||
|
||||
|
||||
// 3:0 ACCEL_ODR
|
||||
// 0001: 32kHz
|
||||
ACCEL_ODR_32KHZ_SET = Bit0,
|
||||
ACCEL_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0,
|
||||
// 0010: 16kHz
|
||||
ACCEL_ODR_16KHZ_SET = Bit1,
|
||||
ACCEL_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0,
|
||||
// 0011: 8kHz
|
||||
ACCEL_ODR_8KHZ_SET = Bit1 | Bit0,
|
||||
ACCEL_ODR_8KHZ_CLEAR = Bit3 | Bit2,
|
||||
// 0110: 1kHz (default)
|
||||
ACCEL_ODR_1KHZ_SET = Bit2 | Bit1,
|
||||
ACCEL_ODR_1KHZ_CLEAR = Bit3 | Bit0,
|
||||
};
|
||||
|
||||
// GYRO_CONFIG1
|
||||
enum GYRO_CONFIG1_BIT : uint8_t {
|
||||
GYRO_UI_FILT_ORD = Bit3 | Bit2, // 00: 1st Order
|
||||
};
|
||||
|
||||
// GYRO_ACCEL_CONFIG0
|
||||
enum GYRO_ACCEL_CONFIG0_BIT : uint8_t {
|
||||
// 7:4 ACCEL_UI_FILT_BW
|
||||
ACCEL_UI_FILT_BW = Bit7 | Bit6 | Bit5 | Bit4, // 0: BW=ODR/2
|
||||
|
||||
// 3:0 GYRO_UI_FILT_BW
|
||||
GYRO_UI_FILT_BW = Bit3 | Bit2 | Bit1 | Bit0, // 0: BW=ODR/2
|
||||
};
|
||||
|
||||
// ACCEL_CONFIG1
|
||||
enum ACCEL_CONFIG1_BIT : uint8_t {
|
||||
ACCEL_UI_FILT_ORD = Bit4 | Bit3, // 00: 1st Order
|
||||
};
|
||||
|
||||
// FIFO_CONFIG1
|
||||
enum FIFO_CONFIG1_BIT : uint8_t {
|
||||
FIFO_RESUME_PARTIAL_RD = Bit6,
|
||||
FIFO_WM_GT_TH = Bit5,
|
||||
FIFO_HIRES_EN = Bit4,
|
||||
FIFO_TEMP_EN = Bit2,
|
||||
FIFO_GYRO_EN = Bit1,
|
||||
FIFO_ACCEL_EN = Bit0,
|
||||
};
|
||||
|
||||
// INT_CONFIG0
|
||||
enum INT_CONFIG0_BIT : uint8_t {
|
||||
// 3:2 FIFO_THS_INT_CLEAR
|
||||
CLEAR_ON_FIFO_READ = Bit3,
|
||||
};
|
||||
|
||||
// INT_SOURCE0
|
||||
enum INT_SOURCE0_BIT : uint8_t {
|
||||
UI_FSYNC_INT1_EN = Bit6,
|
||||
PLL_RDY_INT1_EN = Bit5,
|
||||
RESET_DONE_INT1_EN = Bit4,
|
||||
UI_DRDY_INT1_EN = Bit3,
|
||||
FIFO_THS_INT1_EN = Bit2, // FIFO threshold interrupt routed to INT1
|
||||
FIFO_FULL_INT1_EN = Bit1,
|
||||
UI_AGC_RDY_INT1_EN = Bit0,
|
||||
};
|
||||
|
||||
// REG_BANK_SEL
|
||||
enum REG_BANK_SEL_BIT : uint8_t {
|
||||
USER_BANK_0 = 0, // 0: Select USER BANK 0.
|
||||
USER_BANK_1 = Bit0, // 1: Select USER BANK 1.
|
||||
USER_BANK_2 = Bit1, // 2: Select USER BANK 2.
|
||||
USER_BANK_3 = Bit1 | Bit0, // 3: Select USER BANK 3.
|
||||
};
|
||||
|
||||
|
||||
//---------------- BANK1 Register bits
|
||||
|
||||
// GYRO_CONFIG_STATIC2
|
||||
enum GYRO_CONFIG_STATIC2_BIT : uint8_t {
|
||||
GYRO_AAF_DIS = Bit1,
|
||||
GYRO_NF_DIS = Bit0,
|
||||
};
|
||||
|
||||
// GYRO_CONFIG_STATIC3
|
||||
enum GYRO_CONFIG_STATIC3_BIT : uint8_t {
|
||||
|
||||
// 585 Hz
|
||||
GYRO_AAF_DELT_SET = Bit3 | Bit2 | Bit0, //13
|
||||
GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit1,
|
||||
|
||||
// 213 Hz
|
||||
// GYRO_AAF_DELT_SET = Bit2 | Bit0, //5
|
||||
// GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit1,
|
||||
|
||||
// 126 Hz
|
||||
//GYRO_AAF_DELT_SET = Bit1 | Bit0, //3
|
||||
//GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit2,
|
||||
|
||||
// 42 Hz
|
||||
// GYRO_AAF_DELT_SET = Bit0, //1
|
||||
// GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
|
||||
|
||||
};
|
||||
|
||||
// GYRO_CONFIG_STATIC4
|
||||
enum GYRO_CONFIG_STATIC4_BIT : uint8_t {
|
||||
|
||||
// 585 Hz
|
||||
GYRO_AAF_DELTSQR_LOW_SET = Bit7 | Bit5 | Bit3 | Bit1, //170
|
||||
GYRO_AAF_DELTSQR_LOW_CLEAR = Bit6 | Bit4 | Bit2 | Bit0,
|
||||
|
||||
// 213 Hz
|
||||
// GYRO_AAF_DELTSQR_LOW_SET = Bit4 | Bit3 | Bit0, //25
|
||||
// GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit2 | Bit1,
|
||||
|
||||
// 126 Hz
|
||||
//GYRO_AAF_DELTSQR_LOW_SET = Bit3 | Bit0, //9
|
||||
//GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit2 | Bit1,
|
||||
|
||||
// 42 Hz
|
||||
// GYRO_AAF_DELTSQR_LOW_SET = Bit0, //1
|
||||
// GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
|
||||
};
|
||||
|
||||
// GYRO_CONFIG_STATIC5
|
||||
enum GYRO_CONFIG_STATIC5_BIT : uint8_t {
|
||||
|
||||
// 585 Hz
|
||||
GYRO_AAF_DELTSQR_HIGH_SET = 0,
|
||||
GYRO_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
|
||||
GYRO_AAF_BITSHIFT_SET = Bit7, // 8 << 4
|
||||
GYRO_AAF_BITSHIFT_CLEAR = Bit6 | Bit5 | Bit4,
|
||||
|
||||
// 213 Hz
|
||||
// GYRO_AAF_DELTSQR_HIGH_SET = 0,
|
||||
// GYRO_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
|
||||
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit5, //10
|
||||
// GYRO_AAF_BITSHIFT_CLEAR = Bit6 | Bit4,
|
||||
|
||||
// 126 Hz
|
||||
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit6, //12
|
||||
// GYRO_AAF_BITSHIFT_CLEAR = Bit5 | Bit4,
|
||||
|
||||
// 42 Hz
|
||||
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit6 | Bit5 | Bit4, //15
|
||||
// GYRO_AAF_BITSHIFT_CLEAR = 0,
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
//---------------- BANK2 Register bits
|
||||
|
||||
// ACCEL_CONFIG_STATIC2
|
||||
enum ACCEL_CONFIG_STATIC2_BIT : uint8_t {
|
||||
ACCEL_AAF_DIS = Bit0,
|
||||
ACCEL_AAF_DELT = Bit3 | Bit1,
|
||||
|
||||
// 213 Hz
|
||||
ACCEL_AAF_DELT_SET = Bit3 | Bit1, //5
|
||||
ACCEL_AAF_DELT_CLEAR = Bit6 | Bit5 | Bit4 | Bit2,
|
||||
|
||||
// 42 Hz
|
||||
// ACCEL_AAF_DELT_SET = Bit1, //1
|
||||
// ACCEL_AAF_DELT_CLEAR = Bit6 | Bit5 | Bit4 | Bit3 | Bit2,
|
||||
};
|
||||
|
||||
// ACCEL_CONFIG_STATIC3
|
||||
enum ACCEL_CONFIG_STATIC3_BIT : uint8_t {
|
||||
ACCEL_AAF_DELTSQR_LOW = Bit4 | Bit3 | Bit0,
|
||||
// 213 Hz
|
||||
ACCEL_AAF_DELTSQR_LOW_SET = Bit4 | Bit3 | Bit0, //25
|
||||
ACCEL_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit2 | Bit1,
|
||||
|
||||
// 42 Hz
|
||||
// ACCEL_AAF_DELTSQR_LOW_SET = Bit0, //1
|
||||
// ACCEL_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
|
||||
|
||||
};
|
||||
|
||||
// ACCEL_CONFIG_STATIC4
|
||||
enum ACCEL_CONFIG_STATIC4_BIT : uint8_t {
|
||||
ACCEL_AAF_BITSHIFT = Bit7 | Bit5,
|
||||
ACCEL_AAF_DELTSQR_HIGH = 0,
|
||||
// 213 Hz
|
||||
ACCEL_AAF_BITSHIFT_SET = Bit7 | Bit5, //10
|
||||
ACCEL_AAF_BITSHIFT_CLEAR = Bit6 | Bit4,
|
||||
|
||||
// 42 Hz
|
||||
// ACCEL_AAF_BITSHIFT_SET = Bit7 | Bit6 | Bit5 | Bit4, //15
|
||||
// ACCEL_AAF_BITSHIFT_CLEAR = 0,
|
||||
|
||||
ACCEL_AAF_DELTSQR_HIGH_SET = 0,
|
||||
ACCEL_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
|
||||
};
|
||||
|
||||
|
||||
namespace FIFO
|
||||
{
|
||||
static constexpr size_t SIZE = 2048;
|
||||
|
||||
// FIFO_DATA layout when FIFO_CONFIG1 has FIFO_GYRO_EN and FIFO_ACCEL_EN set
|
||||
|
||||
// Packet 4
|
||||
struct DATA {
|
||||
uint8_t FIFO_Header;
|
||||
uint8_t ACCEL_DATA_X1; // Accel X [19:12]
|
||||
uint8_t ACCEL_DATA_X0; // Accel X [11:4]
|
||||
uint8_t ACCEL_DATA_Y1; // Accel Y [19:12]
|
||||
uint8_t ACCEL_DATA_Y0; // Accel Y [11:4]
|
||||
uint8_t ACCEL_DATA_Z1; // Accel Z [19:12]
|
||||
uint8_t ACCEL_DATA_Z0; // Accel Z [11:4]
|
||||
uint8_t GYRO_DATA_X1; // Gyro X [19:12]
|
||||
uint8_t GYRO_DATA_X0; // Gyro X [11:4]
|
||||
uint8_t GYRO_DATA_Y1; // Gyro Y [19:12]
|
||||
uint8_t GYRO_DATA_Y0; // Gyro Y [11:4]
|
||||
uint8_t GYRO_DATA_Z1; // Gyro Z [19:12]
|
||||
uint8_t GYRO_DATA_Z0; // Gyro Z [11:4]
|
||||
uint8_t TEMP_DATA1; // Temperature[15:8]
|
||||
uint8_t TEMP_DATA0; // Temperature[7:0]
|
||||
uint8_t TimeStamp_h; // TimeStamp[15:8]
|
||||
uint8_t TimeStamp_l; // TimeStamp[7:0]
|
||||
uint8_t Ext_Accel_X_Gyro_X; // Accel X [3:0] Gyro X [3:0]
|
||||
uint8_t Ext_Accel_Y_Gyro_Y; // Accel Y [3:0] Gyro Y [3:0]
|
||||
uint8_t Ext_Accel_Z_Gyro_Z; // Accel Z [3:0] Gyro Z [3:0]
|
||||
};
|
||||
|
||||
// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx
|
||||
enum FIFO_HEADER_BIT : uint8_t {
|
||||
HEADER_MSG = Bit7, // 1: FIFO is empty
|
||||
HEADER_ACCEL = Bit6, // 1: Packet is sized so that accel data have location in the packet, FIFO_ACCEL_EN must be 1
|
||||
HEADER_GYRO = Bit5, // 1: Packet is sized so that gyro data have location in the packet, FIFO_GYRO_EN must be1
|
||||
HEADER_20 = Bit4, // 1: Packet has a new and valid sample of extended 20-bit data for gyro and/or accel
|
||||
HEADER_TIMESTAMP_FSYNC = Bit3 | Bit2,
|
||||
HEADER_ODR_ACCEL = Bit1, // 1: The ODR for accel is different for this accel data packet compared to the previous accel packet
|
||||
HEADER_ODR_GYRO = Bit0, // 1: The ODR for gyro is different for this gyro data packet compared to the previous gyro packet
|
||||
};
|
||||
|
||||
}
|
||||
} // namespace InvenSense_ICM42688P
|
||||
@@ -1,116 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "ICM42688P.hpp"
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <string>
|
||||
|
||||
void ICM42688P::print_usage()
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("icm42688p", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("imu");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
// I2CSPIDriverBase *ICM42688P::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
// int runtime_instance)
|
||||
// {
|
||||
// ICM42688P *instance = new ICM42688P(iterator.configuredBusOption(), iterator.bus(), iterator.devid(), cli.rotation,
|
||||
// cli.bus_frequency, cli.spi_mode, iterator.DRDYGPIO());
|
||||
//
|
||||
// if (!instance) {
|
||||
// PX4_ERR("alloc failed");
|
||||
// return nullptr;
|
||||
// }
|
||||
//
|
||||
// if (OK != instance->init()) {
|
||||
// delete instance;
|
||||
// return nullptr;
|
||||
// }
|
||||
//
|
||||
// return instance;
|
||||
// }
|
||||
|
||||
extern "C" int icm42688p_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
for (int i = 0; i <= argc - 1; i++) {
|
||||
if (std::string(argv[i]) == "-h") {
|
||||
argv[i] = 0;
|
||||
hitl_mode = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int ch;
|
||||
using ThisDriver = ICM42688P;
|
||||
BusCLIArguments cli{false, true};
|
||||
cli.default_spi_frequency = SPI_SPEED;
|
||||
|
||||
while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'R':
|
||||
cli.rotation = (enum Rotation)atoi(cli.optArg());
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const char *verb = cli.optArg();
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_ICM42688P);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
@@ -18,4 +18,4 @@ CONFIG_MODULES_UUV_POS_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
|
||||
@@ -53,7 +53,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
|
||||
@@ -16,7 +16,7 @@ param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 1
|
||||
|
||||
if ver hwbasecmp 008 009 00a 010
|
||||
if ver hwbasecmp 008 009 00a 010 011
|
||||
then
|
||||
# Skynode: use the "custom participant" config for uxrce_dds_client
|
||||
param set-default UXRCE_DDS_PTCFG 2
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
if ver hwbasecmp 008 009 00a 010
|
||||
if ver hwbasecmp 008 009 00a 010 011
|
||||
then
|
||||
# Start MAVLink on the UART connected to the mission computer
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
|
||||
@@ -49,7 +49,7 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwbasecmp 008 009 00a 010
|
||||
if ver hwbasecmp 008 009 00a 010 011
|
||||
then
|
||||
#SKYNODE base fmu board orientation
|
||||
|
||||
|
||||
@@ -1,21 +1,16 @@
|
||||
CONFIG_DRIVERS_IRLOCK=n
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=n
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
|
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=n
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_POS_CONTROL=n
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=n
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=n
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
|
||||
@@ -1,21 +1,16 @@
|
||||
CONFIG_DRIVERS_IRLOCK=n
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=n
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
|
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=n
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_POS_CONTROL=n
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=n
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=n
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
|
||||
@@ -13,4 +13,4 @@ CONFIG_MODULES_MC_RATE_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
|
||||
@@ -18,7 +18,7 @@ param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
# Skynode: use the "custom participant" config for uxrce_dds_client
|
||||
param set-default UXRCE_DDS_PTCFG 2
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# if skynode base board is detected start Mavlink on Telem2
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
|
||||
|
||||
@@ -12,6 +12,7 @@ fi
|
||||
if param compare -s ADC_ADS1115_EN 1
|
||||
then
|
||||
ads1115 start -X
|
||||
board_adc start -n
|
||||
else
|
||||
board_adc start
|
||||
fi
|
||||
@@ -55,7 +56,7 @@ then
|
||||
fi
|
||||
|
||||
#Start Auterion Power Module selector for Skynode boards
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
pm_selector_auterion start
|
||||
else
|
||||
@@ -92,7 +93,7 @@ else
|
||||
icm20649 -s -R 6 start
|
||||
else
|
||||
# Internal SPI BMI088
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
bmi088 -A -R 6 -s start
|
||||
bmi088 -G -R 6 -s start
|
||||
@@ -109,7 +110,7 @@ else
|
||||
fi
|
||||
|
||||
# Internal SPI bus ICM42688p
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
icm42688p -R 12 -s start
|
||||
else
|
||||
@@ -126,7 +127,7 @@ else
|
||||
# Internal SPI bus ICM-42670-P (hard-mounted)
|
||||
icm42670p -R 10 -s start
|
||||
else
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
icm20602 -R 6 -s start
|
||||
else
|
||||
|
||||
@@ -13,4 +13,4 @@ CONFIG_MODULES_MC_RATE_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
|
||||
@@ -6,21 +6,30 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
|
||||
CONFIG_COMMON_INS=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
@@ -32,14 +41,20 @@ CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_COMMON_UWB=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
@@ -57,11 +72,15 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# if skynode base board is detected start Mavlink on Telem2
|
||||
if ver hwbasecmp 009 010
|
||||
if ver hwbasecmp 009 010 011
|
||||
then
|
||||
mavlink start -d /dev/ttyS5 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
|
||||
|
||||
@@ -257,7 +257,7 @@ CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2032
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
|
||||
@@ -1,4 +1,9 @@
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=n
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
|
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=n
|
||||
@@ -6,6 +11,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_POS_CONTROL=n
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
# CONFIG_EKF2_WIND is not set
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
|
||||
@@ -12,7 +12,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
|
||||
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_EKF2_VERBOSE_STATUS=y
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
|
||||
|
||||
@@ -173,6 +173,7 @@ set(msg_files
|
||||
RegisterExtComponentReply.msg
|
||||
RegisterExtComponentRequest.msg
|
||||
Rpm.msg
|
||||
RtlStatus.msg
|
||||
RtlTimeEstimate.msg
|
||||
SatelliteInfo.msg
|
||||
SensorAccel.msg
|
||||
|
||||
@@ -1,4 +1,8 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
float32 speed # [m/s] collective roll-off speed in body x-axis
|
||||
bool closed_loop_speed_control # true if speed is controlled using estimator feedback, false if direct feed-forward
|
||||
float32 yaw_rate # [rad/s] yaw rate
|
||||
bool closed_loop_yaw_rate_control # true if yaw rate is controlled using gyroscope feedback, false if direct feed-forward
|
||||
|
||||
# TOPICS differential_drive_setpoint differential_drive_control_output
|
||||
|
||||
@@ -55,15 +55,9 @@ bool fs_bad_airspeed # 5 - true if fusion of the airspeed has encounte
|
||||
bool fs_bad_sideslip # 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
|
||||
bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis has encountered a numerical error
|
||||
bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error
|
||||
bool fs_bad_vel_n # 9 - true if fusion of the North velocity has encountered a numerical error
|
||||
bool fs_bad_vel_e # 10 - true if fusion of the East velocity has encountered a numerical error
|
||||
bool fs_bad_vel_d # 11 - true if fusion of the Down velocity has encountered a numerical error
|
||||
bool fs_bad_pos_n # 12 - true if fusion of the North position has encountered a numerical error
|
||||
bool fs_bad_pos_e # 13 - true if fusion of the East position has encountered a numerical error
|
||||
bool fs_bad_pos_d # 14 - true if fusion of the Down position has encountered a numerical error
|
||||
bool fs_bad_acc_bias # 15 - true if bad delta velocity bias estimates have been detected
|
||||
bool fs_bad_acc_vertical # 16 - true if bad vertical accelerometer data has been detected
|
||||
bool fs_bad_acc_clipping # 17 - true if delta velocity data contains clipping (asymmetric railing)
|
||||
bool fs_bad_acc_bias # 9 - true if bad delta velocity bias estimates have been detected
|
||||
bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected
|
||||
bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing)
|
||||
|
||||
|
||||
# innovation test failures
|
||||
|
||||
@@ -4,4 +4,6 @@ int32 val
|
||||
|
||||
uint8[64] junk
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 16
|
||||
|
||||
# TOPICS orb_test_medium orb_test_medium_multi orb_test_medium_wrap_around orb_test_medium_queue orb_test_medium_queue_poll
|
||||
|
||||
@@ -0,0 +1,15 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint32 safe_points_id # unique ID of active set of safe_point_items
|
||||
bool is_evaluation_pending # flag if the RTL point needs reevaluation (e.g. new safe points available, but need loading).
|
||||
|
||||
bool has_vtol_approach # flag if approaches are defined for current RTL_TYPE parameter setting
|
||||
|
||||
uint8 rtl_type # Type of RTL chosen
|
||||
uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode
|
||||
|
||||
uint8 RTL_STATUS_TYPE_NONE=0 # RTL type is pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # RTL type is chosen to directly go to a safe point or home position
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # RTL type is going straight to the beginning of the mission landing
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # RTL type is following the mission from closest point to mission landing
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # RTL type is following the mission in reverse to the start position
|
||||
@@ -48,6 +48,8 @@
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdbool.h>
|
||||
#include <syslog.h>
|
||||
@@ -57,7 +59,6 @@
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
|
||||
|
||||
typedef struct {
|
||||
hw_base_id_t hw_base_id; /* The ID of the Base */
|
||||
@@ -292,12 +293,6 @@ static const px4_hw_mft_item_t base_configuration_9[] = {
|
||||
.mandatory = 1,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_PM2,
|
||||
.present = 1,
|
||||
.mandatory = 1,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_ETHERNET,
|
||||
.present = 1,
|
||||
@@ -315,6 +310,52 @@ static const px4_hw_mft_item_t base_configuration_9[] = {
|
||||
// BASE ID 10 Skynode QS no USB Alaised to ID 9
|
||||
// BASE ID 16 Auterion Skynode RC10, RC11, RC12, RC13 Alaised to ID 0
|
||||
|
||||
// BASE ID 17 Auterion Skynode RC13 with many parts removed
|
||||
static const px4_hw_mft_item_t base_configuration_17[] = {
|
||||
{
|
||||
.id = PX4_MFT_PX4IO,
|
||||
.present = 0,
|
||||
.mandatory = 0,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_USB,
|
||||
.present = 1,
|
||||
.mandatory = 1,
|
||||
.connection = px4_hw_con_unknown,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_CAN2,
|
||||
.present = 0,
|
||||
.mandatory = 0,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_CAN3,
|
||||
.present = 0,
|
||||
.mandatory = 0,
|
||||
.connection = px4_hw_con_unknown,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_PM2,
|
||||
.present = 0,
|
||||
.mandatory = 0,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_ETHERNET,
|
||||
.present = 1,
|
||||
.mandatory = 1,
|
||||
.connection = px4_hw_con_connector,
|
||||
},
|
||||
{
|
||||
.id = PX4_MFT_T100_ETH,
|
||||
.present = 1,
|
||||
.mandatory = 1,
|
||||
.connection = px4_hw_con_onboard,
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver_rev
|
||||
@@ -328,6 +369,7 @@ static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{HW_BASE_ID(9), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 9
|
||||
{HW_BASE_ID(10), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 10
|
||||
{HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16
|
||||
{HW_BASE_ID(17), base_configuration_17, arraySize(base_configuration_17)}, // Auterion Skynode ver 17
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
||||
@@ -74,7 +74,7 @@ void px4_log_initialize(void)
|
||||
log_message.severity = 6; // info
|
||||
strcpy((char *)log_message.text, "initialized uORB logging");
|
||||
log_message.timestamp = hrt_absolute_time();
|
||||
orb_log_message_pub = orb_advertise_queue(ORB_ID(log_message), &log_message, log_message_s::ORB_QUEUE_LENGTH);
|
||||
orb_log_message_pub = orb_advertise(ORB_ID(log_message), &log_message);
|
||||
}
|
||||
|
||||
__EXPORT void px4_log_modulename(int level, const char *module_name, const char *fmt, ...)
|
||||
|
||||
@@ -48,24 +48,6 @@
|
||||
namespace uORB
|
||||
{
|
||||
|
||||
template <typename U> class DefaultQueueSize
|
||||
{
|
||||
private:
|
||||
template <typename T>
|
||||
static constexpr uint8_t get_queue_size(decltype(T::ORB_QUEUE_LENGTH) *)
|
||||
{
|
||||
return T::ORB_QUEUE_LENGTH;
|
||||
}
|
||||
|
||||
template <typename T> static constexpr uint8_t get_queue_size(...)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
public:
|
||||
static constexpr unsigned value = get_queue_size<U>(nullptr);
|
||||
};
|
||||
|
||||
class PublicationBase
|
||||
{
|
||||
public:
|
||||
@@ -97,7 +79,7 @@ protected:
|
||||
/**
|
||||
* uORB publication wrapper class
|
||||
*/
|
||||
template<typename T, uint8_t ORB_QSIZE = DefaultQueueSize<T>::value>
|
||||
template<typename T>
|
||||
class Publication : public PublicationBase
|
||||
{
|
||||
public:
|
||||
@@ -113,7 +95,7 @@ public:
|
||||
bool advertise()
|
||||
{
|
||||
if (!advertised()) {
|
||||
_handle = orb_advertise_queue(get_topic(), nullptr, ORB_QSIZE);
|
||||
_handle = orb_advertise(get_topic(), nullptr);
|
||||
}
|
||||
|
||||
return advertised();
|
||||
|
||||
@@ -51,7 +51,7 @@ namespace uORB
|
||||
/**
|
||||
* Base publication multi wrapper class
|
||||
*/
|
||||
template<typename T, uint8_t QSIZE = DefaultQueueSize<T>::value>
|
||||
template<typename T>
|
||||
class PublicationMulti : public PublicationBase
|
||||
{
|
||||
public:
|
||||
@@ -73,7 +73,7 @@ public:
|
||||
{
|
||||
if (!advertised()) {
|
||||
int instance = 0;
|
||||
_handle = orb_advertise_multi_queue(get_topic(), nullptr, &instance, QSIZE);
|
||||
_handle = orb_advertise_multi(get_topic(), nullptr, &instance);
|
||||
}
|
||||
|
||||
return advertised();
|
||||
|
||||
@@ -118,22 +118,11 @@ orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
|
||||
return uORB::Manager::get_instance()->orb_advertise(meta, data);
|
||||
}
|
||||
|
||||
orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data, unsigned int queue_size)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_advertise(meta, data, queue_size);
|
||||
}
|
||||
|
||||
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_advertise_multi(meta, data, instance);
|
||||
}
|
||||
|
||||
orb_advert_t orb_advertise_multi_queue(const struct orb_metadata *meta, const void *data, int *instance,
|
||||
unsigned int queue_size)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_advertise_multi(meta, data, instance, queue_size);
|
||||
}
|
||||
|
||||
int orb_unadvertise(orb_advert_t handle)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_unadvertise(handle);
|
||||
@@ -227,6 +216,14 @@ const char *orb_get_c_type(unsigned char short_type)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
uint8_t orb_get_queue_depth(const struct orb_metadata *meta)
|
||||
{
|
||||
if (meta) {
|
||||
return meta->o_queue;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void orb_print_message_internal(const orb_metadata *meta, const void *data, bool print_topic_name)
|
||||
{
|
||||
|
||||
@@ -53,6 +53,8 @@ struct orb_metadata {
|
||||
const uint16_t o_size_no_padding; /**< object size w/o padding at the end (for logger) */
|
||||
uint32_t message_hash; /**< Hash over all fields for message compatibility checks */
|
||||
orb_id_size_t o_id; /**< ORB_ID enum */
|
||||
uint8_t o_queue; /**< queue size */
|
||||
|
||||
};
|
||||
|
||||
typedef const struct orb_metadata *orb_id_t;
|
||||
@@ -102,14 +104,16 @@ typedef const struct orb_metadata *orb_id_t;
|
||||
* @param _size_no_padding Struct size w/o padding at the end
|
||||
* @param _message_hash 32 bit message hash over all fields
|
||||
* @param _orb_id_enum ORB ID enum e.g.: ORB_ID::vehicle_status
|
||||
* @param _queue_size Queue size from topic definition
|
||||
*/
|
||||
#define ORB_DEFINE(_name, _struct, _size_no_padding, _message_hash, _orb_id_enum) \
|
||||
const struct orb_metadata __orb_##_name = { \
|
||||
#_name, \
|
||||
sizeof(_struct), \
|
||||
_size_no_padding, \
|
||||
_message_hash, \
|
||||
_orb_id_enum \
|
||||
#define ORB_DEFINE(_name, _struct, _size_no_padding, _message_hash, _orb_id_enum, _queue_size) \
|
||||
const struct orb_metadata __orb_##_name = { \
|
||||
#_name, \
|
||||
sizeof(_struct), \
|
||||
_size_no_padding, \
|
||||
_message_hash, \
|
||||
_orb_id_enum, \
|
||||
_queue_size \
|
||||
}; struct hack
|
||||
|
||||
__BEGIN_DECLS
|
||||
@@ -135,23 +139,11 @@ typedef void *orb_advert_t;
|
||||
*/
|
||||
extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
|
||||
|
||||
/**
|
||||
* @see uORB::Manager::orb_advertise()
|
||||
*/
|
||||
extern orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data,
|
||||
unsigned int queue_size) __EXPORT;
|
||||
|
||||
/**
|
||||
* @see uORB::Manager::orb_advertise_multi()
|
||||
*/
|
||||
extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance) __EXPORT;
|
||||
|
||||
/**
|
||||
* @see uORB::Manager::orb_advertise_multi()
|
||||
*/
|
||||
extern orb_advert_t orb_advertise_multi_queue(const struct orb_metadata *meta, const void *data, int *instance,
|
||||
unsigned int queue_size) __EXPORT;
|
||||
|
||||
/**
|
||||
* @see uORB::Manager::orb_unadvertise()
|
||||
*/
|
||||
@@ -160,7 +152,7 @@ extern int orb_unadvertise(orb_advert_t handle) __EXPORT;
|
||||
/**
|
||||
* @see uORB::Manager::orb_publish()
|
||||
*/
|
||||
extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT;
|
||||
extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT;
|
||||
|
||||
/**
|
||||
* Advertise as the publisher of a topic.
|
||||
@@ -241,6 +233,12 @@ extern int orb_get_interval(int handle, unsigned *interval) __EXPORT;
|
||||
*/
|
||||
const char *orb_get_c_type(unsigned char short_type);
|
||||
|
||||
/**
|
||||
* Returns the queue depth of a topic
|
||||
* @param meta orb topic metadata
|
||||
*/
|
||||
extern uint8_t orb_get_queue_depth(const struct orb_metadata *meta);
|
||||
|
||||
/**
|
||||
* Print a topic to console. Do not call this directly, use print_message() instead.
|
||||
* @param meta orb topic metadata
|
||||
|
||||
@@ -73,12 +73,10 @@ static inline uint8_t round_pow_of_two_8(uint8_t n)
|
||||
return value + 1;
|
||||
}
|
||||
|
||||
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path,
|
||||
uint8_t queue_size) :
|
||||
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path) :
|
||||
CDev(strdup(path)), // success is checked in CDev::init
|
||||
_meta(meta),
|
||||
_instance(instance),
|
||||
_queue_size(round_pow_of_two_8(queue_size))
|
||||
_instance(instance)
|
||||
{
|
||||
}
|
||||
|
||||
@@ -186,7 +184,7 @@ uORB::DeviceNode::write(cdev::file_t *filp, const char *buffer, size_t buflen)
|
||||
|
||||
/* re-check size */
|
||||
if (nullptr == _data) {
|
||||
const size_t data_size = _meta->o_size * _queue_size;
|
||||
const size_t data_size = _meta->o_size * _meta->o_queue;
|
||||
_data = (uint8_t *) px4_cache_aligned_alloc(data_size);
|
||||
|
||||
if (_data) {
|
||||
@@ -217,7 +215,7 @@ uORB::DeviceNode::write(cdev::file_t *filp, const char *buffer, size_t buflen)
|
||||
/* wrap-around happens after ~49 days, assuming a publisher rate of 1 kHz */
|
||||
unsigned generation = _generation.fetch_add(1);
|
||||
|
||||
memcpy(_data + (_meta->o_size * (generation % _queue_size)), buffer, _meta->o_size);
|
||||
memcpy(_data + (_meta->o_size * (generation % _meta->o_queue)), buffer, _meta->o_size);
|
||||
|
||||
// callbacks
|
||||
for (auto item : _callbacks) {
|
||||
@@ -254,13 +252,6 @@ uORB::DeviceNode::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
|
||||
*(uintptr_t *)arg = (uintptr_t)this;
|
||||
return PX4_OK;
|
||||
|
||||
case ORBIOCSETQUEUESIZE: {
|
||||
lock();
|
||||
int ret = update_queue_size(arg);
|
||||
unlock();
|
||||
return ret;
|
||||
}
|
||||
|
||||
case ORBIOCGETINTERVAL:
|
||||
*(unsigned *)arg = filp_to_subscription(filp)->get_interval_us();
|
||||
return PX4_OK;
|
||||
@@ -389,12 +380,11 @@ uORB::DeviceNode::print_statistics(int max_topic_length)
|
||||
|
||||
const uint8_t instance = get_instance();
|
||||
const int8_t sub_count = subscriber_count();
|
||||
const uint8_t queue_size = get_queue_size();
|
||||
|
||||
unlock();
|
||||
|
||||
PX4_INFO_RAW("%-*s %2i %4i %2i %4i %s\n", max_topic_length, get_meta()->o_name, (int)instance, (int)sub_count,
|
||||
queue_size, get_meta()->o_size, get_devname());
|
||||
get_meta()->o_queue, get_meta()->o_size, get_devname());
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -483,21 +473,6 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data
|
||||
}
|
||||
#endif /* CONFIG_ORB_COMMUNICATOR */
|
||||
|
||||
int uORB::DeviceNode::update_queue_size(unsigned int queue_size)
|
||||
{
|
||||
if (_queue_size == queue_size) {
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
//queue size is limited to 255 for the single reason that we use uint8 to store it
|
||||
if (_data || _queue_size > queue_size || queue_size > 255) {
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
_queue_size = round_pow_of_two_8(queue_size);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
unsigned uORB::DeviceNode::get_initial_generation()
|
||||
{
|
||||
ATOMIC_ENTER;
|
||||
|
||||
@@ -62,7 +62,7 @@ class UnitTest;
|
||||
class uORB::DeviceNode : public cdev::CDev, public IntrusiveSortedListNode<uORB::DeviceNode *>
|
||||
{
|
||||
public:
|
||||
DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path, uint8_t queue_size = 1);
|
||||
DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path);
|
||||
virtual ~DeviceNode();
|
||||
|
||||
// no copy, assignment, move, move assignment
|
||||
@@ -179,15 +179,6 @@ public:
|
||||
|
||||
void mark_as_advertised() { _advertised = true; }
|
||||
|
||||
/**
|
||||
* Try to change the size of the queue. This can only be done as long as nobody published yet.
|
||||
* This is the case, for example when orb_subscribe was called before an orb_advertise.
|
||||
* The queue size can only be increased.
|
||||
* @param queue_size new size of the queue
|
||||
* @return PX4_OK if queue size successfully set
|
||||
*/
|
||||
int update_queue_size(unsigned int queue_size);
|
||||
|
||||
/**
|
||||
* Print statistics
|
||||
* @param max_topic_length max topic name length for printing
|
||||
@@ -195,7 +186,7 @@ public:
|
||||
*/
|
||||
bool print_statistics(int max_topic_length);
|
||||
|
||||
uint8_t get_queue_size() const { return _queue_size; }
|
||||
uint8_t get_queue_size() const { return _meta->o_queue; }
|
||||
|
||||
int8_t subscriber_count() const { return _subscriber_count; }
|
||||
|
||||
@@ -234,7 +225,7 @@ public:
|
||||
bool copy(void *dst, unsigned &generation)
|
||||
{
|
||||
if ((dst != nullptr) && (_data != nullptr)) {
|
||||
if (_queue_size == 1) {
|
||||
if (_meta->o_queue == 1) {
|
||||
ATOMIC_ENTER;
|
||||
memcpy(dst, _data, _meta->o_size);
|
||||
generation = _generation.load();
|
||||
@@ -253,12 +244,12 @@ public:
|
||||
}
|
||||
|
||||
// Compatible with normal and overflow conditions
|
||||
if (!is_in_range(current_generation - _queue_size, generation, current_generation - 1)) {
|
||||
if (!is_in_range(current_generation - _meta->o_queue, generation, current_generation - 1)) {
|
||||
// Reader is too far behind: some messages are lost
|
||||
generation = current_generation - _queue_size;
|
||||
generation = current_generation - _meta->o_queue;
|
||||
}
|
||||
|
||||
memcpy(dst, _data + (_meta->o_size * (generation % _queue_size)), _meta->o_size);
|
||||
memcpy(dst, _data + (_meta->o_size * (generation % _meta->o_queue)), _meta->o_size);
|
||||
ATOMIC_LEAVE;
|
||||
|
||||
++generation;
|
||||
@@ -295,7 +286,7 @@ private:
|
||||
|
||||
const uint8_t _instance; /**< orb multi instance identifier */
|
||||
bool _advertised{false}; /**< has ever been advertised (not necessarily published data yet) */
|
||||
uint8_t _queue_size; /**< maximum number of elements in the queue */
|
||||
|
||||
int8_t _subscriber_count{0};
|
||||
|
||||
|
||||
|
||||
@@ -265,8 +265,7 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
|
||||
return ret;
|
||||
}
|
||||
|
||||
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
|
||||
unsigned int queue_size)
|
||||
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance)
|
||||
{
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
@@ -300,19 +299,10 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
/* Set the queue size. This must be done before the first publication; thus it fails if
|
||||
* this is not the first advertiser.
|
||||
*/
|
||||
int result = px4_ioctl(fd, ORBIOCSETQUEUESIZE, (unsigned long)queue_size);
|
||||
|
||||
if (result < 0 && queue_size > 1) {
|
||||
PX4_WARN("orb_advertise_multi: failed to set queue size");
|
||||
}
|
||||
|
||||
/* get the advertiser handle and close the node */
|
||||
orb_advert_t advertiser;
|
||||
|
||||
result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
|
||||
int result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
|
||||
px4_close(fd);
|
||||
|
||||
if (result == PX4_ERROR) {
|
||||
@@ -602,6 +592,22 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name)
|
||||
{
|
||||
PX4_DEBUG("entering process_remote_topic: name: %s", topic_name);
|
||||
|
||||
// First make sure this is a valid topic
|
||||
const struct orb_metadata *const *topic_list = orb_get_topics();
|
||||
orb_id_t topic_ptr = nullptr;
|
||||
|
||||
for (size_t i = 0; i < orb_topics_count(); i++) {
|
||||
if (strcmp(topic_list[i]->o_name, topic_name) == 0) {
|
||||
topic_ptr = topic_list[i];
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (! topic_ptr) {
|
||||
PX4_ERR("process_remote_topic meta not found for %s\n", topic_name);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Look to see if we already have a node for this topic
|
||||
char nodepath[orb_maxpath];
|
||||
int ret = uORB::Utils::node_mkpath(nodepath, topic_name);
|
||||
@@ -613,7 +619,7 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name)
|
||||
uORB::DeviceNode *node = device_master->getDeviceNode(nodepath);
|
||||
|
||||
if (node) {
|
||||
PX4_INFO("Marking DeviceNode(%s) as advertised in process_remote_topic", topic_name);
|
||||
PX4_DEBUG("Marking DeviceNode(%s) as advertised in process_remote_topic", topic_name);
|
||||
node->mark_as_advertised();
|
||||
_remote_topics.insert(topic_name);
|
||||
return 0;
|
||||
@@ -622,27 +628,9 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name)
|
||||
}
|
||||
|
||||
// We didn't find a node so we need to create it via an advertisement
|
||||
const struct orb_metadata *const *topic_list = orb_get_topics();
|
||||
orb_id_t topic_ptr = nullptr;
|
||||
|
||||
for (size_t i = 0; i < orb_topics_count(); i++) {
|
||||
if (strcmp(topic_list[i]->o_name, topic_name) == 0) {
|
||||
topic_ptr = topic_list[i];
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (topic_ptr) {
|
||||
PX4_INFO("Advertising remote topic %s", topic_name);
|
||||
_remote_topics.insert(topic_name);
|
||||
// Add some queue depth when advertising remote topics. These
|
||||
// topics may get aggregated and thus delivered in a batch that
|
||||
// requires some buffering in a queue.
|
||||
orb_advertise(topic_ptr, nullptr, 5);
|
||||
|
||||
} else {
|
||||
PX4_INFO("process_remote_topic meta not found for %s\n", topic_name);
|
||||
}
|
||||
PX4_DEBUG("Advertising remote topic %s", topic_name);
|
||||
_remote_topics.insert(topic_name);
|
||||
orb_advertise(topic_ptr, nullptr, topic_ptr->o_queue);
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -663,8 +651,11 @@ int16_t uORB::Manager::process_add_subscription(const char *messageName)
|
||||
PX4_DEBUG("DeviceNode(%s) not created yet", messageName);
|
||||
|
||||
} else {
|
||||
// node is present.
|
||||
node->process_add_subscription();
|
||||
// node is present. But don't send any data to it if it
|
||||
// is a node advertised by the remote side
|
||||
if (_remote_topics.find(messageName) == false) {
|
||||
node->process_add_subscription();
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
@@ -215,17 +215,15 @@ public:
|
||||
* @param data A pointer to the initial data to be published.
|
||||
* For topics updated by interrupt handlers, the advertisement
|
||||
* must be performed from non-interrupt context.
|
||||
* @param queue_size Maximum number of buffered elements. If this is 1, no queuing is
|
||||
* used.
|
||||
* @return nullptr on error, otherwise returns an object pointer
|
||||
* that can be used to publish to the topic.
|
||||
* If the topic in question is not known (due to an
|
||||
* ORB_DEFINE with no corresponding ORB_DECLARE)
|
||||
* this function will return nullptr and set errno to ENOENT.
|
||||
*/
|
||||
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data, unsigned int queue_size = 1)
|
||||
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data = nullptr)
|
||||
{
|
||||
return orb_advertise_multi(meta, data, nullptr, queue_size);
|
||||
return orb_advertise_multi(meta, data, nullptr);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -250,16 +248,13 @@ public:
|
||||
* @param instance Pointer to an integer which will yield the instance ID (0-based)
|
||||
* of the publication. This is an output parameter and will be set to the newly
|
||||
* created instance, ie. 0 for the first advertiser, 1 for the next and so on.
|
||||
* @param queue_size Maximum number of buffered elements. If this is 1, no queuing is
|
||||
* used.
|
||||
* @return nullptr on error, otherwise returns a handle
|
||||
* that can be used to publish to the topic.
|
||||
* If the topic in question is not known (due to an
|
||||
* ORB_DEFINE with no corresponding ORB_DECLARE)
|
||||
* this function will return nullptr and set errno to ENOENT.
|
||||
*/
|
||||
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
|
||||
unsigned int queue_size = 1);
|
||||
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance);
|
||||
|
||||
/**
|
||||
* Unadvertise a topic.
|
||||
|
||||
@@ -89,8 +89,7 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
|
||||
return data.ret;
|
||||
}
|
||||
|
||||
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
|
||||
unsigned int queue_size)
|
||||
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance)
|
||||
{
|
||||
/* open the node as an advertiser */
|
||||
int fd = node_open(meta, true, instance);
|
||||
@@ -100,19 +99,10 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
/* Set the queue size. This must be done before the first publication; thus it fails if
|
||||
* this is not the first advertiser.
|
||||
*/
|
||||
int result = px4_ioctl(fd, ORBIOCSETQUEUESIZE, (unsigned long)queue_size);
|
||||
|
||||
if (result < 0 && queue_size > 1) {
|
||||
PX4_WARN("orb_advertise_multi: failed to set queue size");
|
||||
}
|
||||
|
||||
/* get the advertiser handle and close the node */
|
||||
orb_advert_t advertiser;
|
||||
|
||||
result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
|
||||
int result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
|
||||
px4_close(fd);
|
||||
|
||||
if (result == PX4_ERROR) {
|
||||
|
||||
@@ -574,8 +574,8 @@ int uORBTest::UnitTest::test_wrap_around()
|
||||
bool updated{false};
|
||||
|
||||
// Advertise but not publish topics, only generate device_node, which is convenient for modifying DeviceNode::_generation
|
||||
const int queue_size = 16;
|
||||
ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_wrap_around), nullptr, queue_size);
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
ptopic = orb_advertise(ORB_ID(orb_test_medium_wrap_around), nullptr);
|
||||
|
||||
if (ptopic == nullptr) {
|
||||
return test_fail("advertise failed: %d", errno);
|
||||
@@ -828,9 +828,9 @@ int uORBTest::UnitTest::test_queue()
|
||||
return test_fail("subscribe failed: %d", errno);
|
||||
}
|
||||
|
||||
const int queue_size = 16;
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
orb_test_medium_s t{};
|
||||
ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue), &t, queue_size);
|
||||
ptopic = orb_advertise(ORB_ID(orb_test_medium_queue), &t);
|
||||
|
||||
if (ptopic == nullptr) {
|
||||
return test_fail("advertise failed: %d", errno);
|
||||
@@ -935,9 +935,9 @@ int uORBTest::UnitTest::pub_test_queue_main()
|
||||
{
|
||||
orb_test_medium_s t{};
|
||||
orb_advert_t ptopic{nullptr};
|
||||
const int queue_size = 50;
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
|
||||
if ((ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue_poll), &t, queue_size)) == nullptr) {
|
||||
if ((ptopic = orb_advertise(ORB_ID(orb_test_medium_queue_poll), &t)) == nullptr) {
|
||||
_thread_should_exit = true;
|
||||
return test_fail("advertise failed: %d", errno);
|
||||
}
|
||||
|
||||
Submodule platforms/nuttx/NuttX/apps updated: 616f7024a4...e37940d853
@@ -40,15 +40,34 @@
|
||||
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#if defined(CONFIG_MODULES_MUORB_APPS)
|
||||
extern "C" { int muorb_init(); }
|
||||
#endif
|
||||
|
||||
int px4_platform_init(void)
|
||||
{
|
||||
hrt_init();
|
||||
|
||||
px4::WorkQueueManagerStart();
|
||||
|
||||
// MUORB has slightly different startup requirements
|
||||
#if defined(CONFIG_MODULES_MUORB_APPS)
|
||||
//Put sleeper in here to allow wq to finish initializing before param_init is called
|
||||
usleep(10000);
|
||||
|
||||
uorb_start();
|
||||
|
||||
muorb_init();
|
||||
|
||||
// Give muorb some time to setup the DSP
|
||||
usleep(100000);
|
||||
|
||||
param_init();
|
||||
#else
|
||||
param_init();
|
||||
|
||||
uorb_start();
|
||||
#endif
|
||||
|
||||
px4_log_initialize();
|
||||
|
||||
|
||||
@@ -45,28 +45,10 @@
|
||||
namespace uORB
|
||||
{
|
||||
|
||||
template <typename U> class DefaultQueueSize
|
||||
{
|
||||
private:
|
||||
template <typename T>
|
||||
static constexpr uint8_t get_queue_size(decltype(T::ORB_QUEUE_LENGTH) *)
|
||||
{
|
||||
return T::ORB_QUEUE_LENGTH;
|
||||
}
|
||||
|
||||
template <typename T> static constexpr uint8_t get_queue_size(...)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
public:
|
||||
static constexpr unsigned value = get_queue_size<U>(nullptr);
|
||||
};
|
||||
|
||||
/**
|
||||
* uORB publication wrapper class
|
||||
*/
|
||||
template<typename T, uint8_t ORB_QSIZE = DefaultQueueSize<T>::value>
|
||||
template<typename T>
|
||||
class Publication
|
||||
{
|
||||
public:
|
||||
|
||||
@@ -77,6 +77,7 @@ BMP388::init()
|
||||
|
||||
if (_chip_id == BMP390_CHIP_ID) {
|
||||
_interface->set_device_type(DRV_BARO_DEVTYPE_BMP390);
|
||||
this->_item_name = "bmp390";
|
||||
}
|
||||
|
||||
_chip_rev_id = _interface->get_reg(BMP3_REV_ID_ADDR);
|
||||
|
||||
@@ -251,7 +251,7 @@ ICP201XX::RunImpl()
|
||||
case STATE::CONFIG: {
|
||||
if (configure()) {
|
||||
_state = STATE::WAIT_READ;
|
||||
ScheduleDelayed(30_ms);
|
||||
ScheduleDelayed(50_ms);
|
||||
|
||||
} else {
|
||||
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
|
||||
|
||||
@@ -392,6 +392,12 @@ int BATT_SMBUS::get_startup_info()
|
||||
uint16_t state_of_health;
|
||||
ret |= _interface->read_word(BATT_SMBUS_STATE_OF_HEALTH, state_of_health);
|
||||
|
||||
/* ManufacturerAccess dummy command to init the ManufacturerBlockAccess routine
|
||||
in the BQ40Zx0 and avoid timeout during LifetimeDataFlush.
|
||||
test Sleep > 20 ms to give time to init the ManufacturerBlockAccess routine*/
|
||||
ret |= _interface->write_word(BATT_SMBUS_MANUFACTURER_ACCESS, BATT_SMBUS_DEVICE_TYPE);
|
||||
px4_usleep(30_ms);
|
||||
|
||||
if (!ret) {
|
||||
_serial_number = serial_num;
|
||||
_batt_startup_capacity = (uint16_t)((float)remaining_cap * _c_mult);
|
||||
|
||||
@@ -107,6 +107,7 @@ using namespace time_literals;
|
||||
|
||||
#define BATT_SMBUS_SECURITY_KEYS 0x0035
|
||||
|
||||
#define BATT_SMBUS_DEVICE_TYPE 0x0001
|
||||
#define BATT_SMBUS_LIFETIME_FLUSH 0x002E
|
||||
#define BATT_SMBUS_LIFETIME_BLOCK_ONE 0x0060
|
||||
#define BATT_SMBUS_ENABLED_PROTECTIONS_A_ADDRESS 0x4938
|
||||
|
||||
@@ -314,7 +314,7 @@ CameraTrigger::CameraTrigger() :
|
||||
// Advertise critical publishers here, because we cannot advertise in interrupt context
|
||||
camera_trigger_s trigger{};
|
||||
|
||||
_trigger_pub = orb_advertise_queue(ORB_ID(camera_trigger), &trigger, camera_trigger_s::ORB_QUEUE_LENGTH);
|
||||
_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger);
|
||||
}
|
||||
|
||||
CameraTrigger::~CameraTrigger()
|
||||
|
||||
@@ -113,7 +113,7 @@ CM8JL65::CM8JL65(const char *port, uint8_t rotation) :
|
||||
_px4_rangefinder.set_max_distance(7.9f); // Datasheet: 8.0m
|
||||
_px4_rangefinder.set_fov(0.0488692f);
|
||||
_px4_rangefinder.set_device_type(DRV_DIST_DEVTYPE_CM8JL65);
|
||||
_px4_rangefinder.set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER);
|
||||
_px4_rangefinder.set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_INFRARED);
|
||||
}
|
||||
|
||||
CM8JL65::~CM8JL65()
|
||||
|
||||
@@ -64,13 +64,10 @@
|
||||
/** Get the priority for the topic */
|
||||
#define ORBIOCGPRIORITY _ORBIOC(14)
|
||||
|
||||
/** Set the queue size of the topic */
|
||||
#define ORBIOCSETQUEUESIZE _ORBIOC(15)
|
||||
|
||||
/** Get the minimum interval at which the topic can be seen to be updated for this subscription */
|
||||
#define ORBIOCGETINTERVAL _ORBIOC(16)
|
||||
#define ORBIOCGETINTERVAL _ORBIOC(15)
|
||||
|
||||
/** Check whether the topic is advertised, sets *(unsigned long *)arg to 1 if advertised, 0 otherwise */
|
||||
#define ORBIOCISADVERTISED _ORBIOC(17)
|
||||
#define ORBIOCISADVERTISED _ORBIOC(16)
|
||||
|
||||
#endif /* _DRV_UORB_H */
|
||||
|
||||
+1
-1
Submodule src/drivers/gps/devices updated: 836b24c10e...17c0e2bfad
@@ -88,7 +88,7 @@ private:
|
||||
FIFO::DATA f[FIFO_MAX_SAMPLES] {};
|
||||
};
|
||||
// ensure no struct padding
|
||||
static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA)));
|
||||
static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA)), "Invalid transfer buffer size");
|
||||
|
||||
struct register_bank0_config_t {
|
||||
Register::BANK_0 reg;
|
||||
|
||||
@@ -229,7 +229,7 @@ void PWMOut::update_params()
|
||||
if (output_function >= (int)OutputFunction::Servo1
|
||||
&& output_function <= (int)OutputFunction::ServoMax) { // Function got set to a servo
|
||||
int32_t val = 1500;
|
||||
PX4_INFO("Setting channel %i disarmed to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i disarmed to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.disarmedParamHandle(i), &val);
|
||||
|
||||
// If the whole timer group was not set previously, then set the pwm rate to 50 Hz
|
||||
@@ -250,7 +250,7 @@ void PWMOut::update_params()
|
||||
|
||||
if (param_get(handle, &tim_config) == 0 && tim_config == 400) {
|
||||
tim_config = 50;
|
||||
PX4_INFO("setting timer %i to %i Hz", timer, (int) tim_config);
|
||||
PX4_INFO("Setting timer %i to %i Hz", timer, (int)tim_config);
|
||||
param_set(handle, &tim_config);
|
||||
}
|
||||
}
|
||||
@@ -261,10 +261,10 @@ void PWMOut::update_params()
|
||||
if (output_function >= (int)OutputFunction::Motor1
|
||||
&& output_function <= (int)OutputFunction::MotorMax) { // Function got set to a motor
|
||||
int32_t val = 1100;
|
||||
PX4_INFO("Setting channel %i minimum to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i minimum to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.minParamHandle(i), &val);
|
||||
val = 1900;
|
||||
PX4_INFO("Setting channel %i maximum to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i maximum to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.maxParamHandle(i), &val);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -705,7 +705,7 @@ void PX4IO::update_params()
|
||||
if (output_function >= (int)OutputFunction::Servo1
|
||||
&& output_function <= (int)OutputFunction::ServoMax) { // Function got set to a servo
|
||||
int32_t val = 1500;
|
||||
PX4_INFO("Setting channel %i disarmed to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i disarmed to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.disarmedParamHandle(i), &val);
|
||||
|
||||
// If the whole timer group was not set previously, then set the pwm rate to 50 Hz
|
||||
@@ -726,7 +726,7 @@ void PX4IO::update_params()
|
||||
|
||||
if (param_get(handle, &tim_config) == 0 && tim_config == 400) {
|
||||
tim_config = 50;
|
||||
PX4_INFO("setting timer %i to %i Hz", timer, (int) tim_config);
|
||||
PX4_INFO("Setting timer %i to %i Hz", timer, (int)tim_config);
|
||||
param_set(handle, &tim_config);
|
||||
}
|
||||
}
|
||||
@@ -737,10 +737,10 @@ void PX4IO::update_params()
|
||||
if (output_function >= (int)OutputFunction::Motor1
|
||||
&& output_function <= (int)OutputFunction::MotorMax) { // Function got set to a motor
|
||||
int32_t val = 1100;
|
||||
PX4_INFO("Setting channel %i minimum to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i minimum to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.minParamHandle(i), &val);
|
||||
val = 1900;
|
||||
PX4_INFO("Setting channel %i maximum to %i", (int) val, i);
|
||||
PX4_INFO("Setting channel %i maximum to %i", i + 1, (int)val);
|
||||
param_set(_mixing_output.maxParamHandle(i), &val);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -45,8 +45,6 @@ using namespace time_literals;
|
||||
ToneAlarm::ToneAlarm() :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default)
|
||||
{
|
||||
// ensure ORB_ID(tune_control) is advertised with correct queue depth
|
||||
orb_advertise_queue(ORB_ID(tune_control), nullptr, tune_control_s::ORB_QUEUE_LENGTH);
|
||||
}
|
||||
|
||||
ToneAlarm::~ToneAlarm()
|
||||
|
||||
@@ -45,6 +45,7 @@ px4_add_module(
|
||||
voxl2_io.cpp
|
||||
voxl2_io.hpp
|
||||
DEPENDS
|
||||
rc
|
||||
px4_work_queue
|
||||
mixer_module
|
||||
MODULE_CONFIG
|
||||
|
||||
@@ -151,7 +151,7 @@ private:
|
||||
|
||||
transponder_report_s tr{};
|
||||
|
||||
orb_advert_t fake_traffic_report_publisher = orb_advertise_queue(ORB_ID(transponder_report), &tr, (unsigned int)20);
|
||||
orb_advert_t fake_traffic_report_publisher = orb_advertise(ORB_ID(transponder_report), &tr);
|
||||
|
||||
TRAFFIC_STATE _traffic_state_previous{TRAFFIC_STATE::NO_CONFLICT};
|
||||
|
||||
|
||||
@@ -61,7 +61,7 @@ void send(EventType &event)
|
||||
orb_publish(ORB_ID(event), orb_event_pub, &event);
|
||||
|
||||
} else {
|
||||
orb_event_pub = orb_advertise_queue(ORB_ID(event), &event, event_s::ORB_QUEUE_LENGTH);
|
||||
orb_event_pub = orb_advertise(ORB_ID(event), &event);
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&publish_event_mutex);
|
||||
|
||||
@@ -42,7 +42,7 @@ class GeoTest : public ::testing::Test
|
||||
public:
|
||||
void SetUp() override
|
||||
{
|
||||
proj.initReference(math::radians(473566094 / 1e7), math::radians(85190237 / 1e7), 0);
|
||||
proj.initReference(473566094 / 1e7, 85190237 / 1e7, 0);
|
||||
}
|
||||
|
||||
protected:
|
||||
@@ -73,7 +73,7 @@ TEST_F(GeoTest, reprojectProject)
|
||||
|
||||
TEST_F(GeoTest, projectReproject)
|
||||
{
|
||||
// GIVEN: x and y coordinates in the local cartesian frame
|
||||
// GIVEN: lat and lon coordinates in the geographic coordinate system
|
||||
double lat = 47.356616973876953;
|
||||
double lon = 8.5190505981445313;
|
||||
float x;
|
||||
|
||||
@@ -162,6 +162,24 @@ public:
|
||||
return res;
|
||||
}
|
||||
|
||||
// Using this function reduces the number of temporary variables needed to compute A * B.T
|
||||
template<size_t P>
|
||||
Matrix<Type, M, M> multiplyByTranspose(const Matrix<Type, P, N> &other) const
|
||||
{
|
||||
Matrix<Type, M, P> res;
|
||||
const Matrix<Type, M, N> &self = *this;
|
||||
|
||||
for (size_t i = 0; i < M; i++) {
|
||||
for (size_t k = 0; k < P; k++) {
|
||||
for (size_t j = 0; j < N; j++) {
|
||||
res(i, k) += self(i, j) * other(k, j);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
// Element-wise multiplication
|
||||
Matrix<Type, M, N> emult(const Matrix<Type, M, N> &other) const
|
||||
{
|
||||
@@ -391,12 +409,6 @@ public:
|
||||
for (unsigned j = 0; j < N; j++) {
|
||||
double d = static_cast<double>(self(i, j));
|
||||
|
||||
// Matrix diagonal elements
|
||||
if (N > 1 && M > 1 && i == j) {
|
||||
// make diagonal elements bold (ANSI CSI n 1)
|
||||
printf("\033[1m");
|
||||
}
|
||||
|
||||
// if symmetric don't print upper triangular elements
|
||||
if ((M == N) && (j > i) && (i < N) && (j < M)
|
||||
&& (fabs(d - static_cast<double>(self(j, i))) < (double)eps)
|
||||
@@ -417,12 +429,6 @@ public:
|
||||
printf("% 6.5f ", d);
|
||||
}
|
||||
}
|
||||
|
||||
// Matrix diagonal elements
|
||||
if (N > 1 && M > 1 && i == j) {
|
||||
// reset any formatting (ANSI CSI n 0)
|
||||
printf("\033[0m");
|
||||
}
|
||||
}
|
||||
|
||||
printf("\n");
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user