mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-03 14:00:05 +08:00
Compare commits
85 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 461224dd4d | |||
| a80a5a92f4 | |||
| b81ad8841e | |||
| 57df7e35b2 | |||
| 006dcfafb7 | |||
| 85a882e1ce | |||
| 04099ed483 | |||
| 1aa26a5a91 | |||
| acd750e033 | |||
| 6c6142ba79 | |||
| 7fb584adbe | |||
| fb3aab1fb0 | |||
| 1b03ac4d2b | |||
| 815cea2abb | |||
| 51321c605e | |||
| a0ae073d8c | |||
| 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 | |||
| 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 |
@@ -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",
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -253,7 +253,7 @@ fi
|
||||
tone_alarm start
|
||||
rc_update start
|
||||
manual_control start
|
||||
#sensors start
|
||||
sensors start
|
||||
commander start
|
||||
|
||||
if ! pwm_out_sim start -m sim
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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: f1c461fffb...6b4ed09d1b
@@ -4,7 +4,7 @@
|
||||
"description": "Firmware for the ARK flow board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "ARFFLOW",
|
||||
"summary": "ARKFLOW",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2080768,
|
||||
|
||||
@@ -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,48 +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.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__imu__invensense__icm42688p
|
||||
MAIN icm42688p
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
icm42688p_main.cpp
|
||||
ICM42688P.cpp
|
||||
ICM42688P.hpp
|
||||
InvenSense_ICM42688P_registers.hpp
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
drivers_accelerometer
|
||||
drivers_gyroscope
|
||||
drivers__device
|
||||
)
|
||||
@@ -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;
|
||||
}
|
||||
@@ -1,9 +1,11 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
@@ -25,6 +27,7 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
@@ -96,4 +99,3 @@ CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
CONFIG_EXAMPLES_FAKE_GPS=y
|
||||
|
||||
@@ -6,4 +6,4 @@
|
||||
param set-default BAT1_V_DIV 10.1
|
||||
param set-default BAT1_A_PER_V 17
|
||||
|
||||
safety_button start
|
||||
param set-default TEL_FRSKY_CONFIG 103
|
||||
|
||||
@@ -16,3 +16,5 @@ icm20948 -s -b 1 -R 8 -M start
|
||||
|
||||
# Interal DPS310 (barometer)
|
||||
dps310 -s -b 2 start
|
||||
|
||||
safety_button start
|
||||
|
||||
@@ -15,7 +15,7 @@ CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-classic/nuttx-con
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743II=y
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
|
||||
@@ -222,6 +222,9 @@
|
||||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
@@ -235,9 +238,6 @@
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
#define GPIO_USART6_TX 0 /* USART6 is RX-only */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
@@ -268,13 +268,14 @@
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_4 /* PB6 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_4 /* PB7 */
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
||||
|
||||
@@ -56,7 +56,7 @@ CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-classic/nuttx-con
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743II=y
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
@@ -192,7 +192,6 @@ CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
@@ -212,17 +211,20 @@ CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI5_DMA=y
|
||||
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_TIM15=y
|
||||
CONFIG_STM32H7_TIM16=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
@@ -252,9 +254,6 @@ CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
|
||||
@@ -45,95 +45,111 @@
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
|
||||
#define GPIO_nLED_RED /* PB11 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_nLED_GREEN /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_nLED_RED /* PB4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_nLED_GREEN /* PB5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nLED_BLUE /* PB3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
#define GPIO_LED_SAFETY /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6)
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_OVERLOAD_LED LED_RED
|
||||
#define BOARD_ARMED_STATE_LED LED_BLUE
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA2 */ GPIO_ADC12_INP14, \
|
||||
/* PC4 */ GPIO_ADC12_INP4, \
|
||||
/* PA3 */ GPIO_ADC12_INP15, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PC1 */ GPIO_ADC123_INP11
|
||||
/* PC0 */ GPIO_ADC123_INP10, \
|
||||
/* PC5 */ GPIO_ADC12_INP8, \
|
||||
/* PB0 */ GPIO_ADC12_INP9, \
|
||||
/* PB1 */ GPIO_ADC12_INP5
|
||||
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 14 /* PA2 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 4 /* PC4 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 15 /* PA3 BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 18 /* PA4 VDD_5V_SENS */
|
||||
#define ADC_RC_RSSI_CHANNEL 11 /* PC1 */
|
||||
#define ADC_RC_RSSI_CHANNEL 10 /* PC0 */
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 8 /* PC5 */
|
||||
#define ADC_AUX1_VOLTAGE_CHANNEL 9 /* PB0 */
|
||||
#define ADC_AUX2_VOLTAGE_CHANNEL 5 /* PB1 */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_RC_RSSI_CHANNEL))
|
||||
(1 << ADC_RC_RSSI_CHANNEL) | \
|
||||
(1 << ADC_AIRSPEED_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_AUX1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_AUX2_VOLTAGE_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* CAN Silence: Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN12)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 12
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nPOWER_IN_A /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
#define GPIO_VDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
|
||||
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
#define GPIO_LEVEL_SHIFTER_OE /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (!on_true))
|
||||
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() (px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) == 0)
|
||||
|
||||
/* Tone alarm output */
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */
|
||||
#define TONE_ALARM_TIMER 16 /* timer 16 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PF6 TIM16_CH1 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_BUZZER_1 /* PF6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN6)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
|
||||
#define GPIO_TONE_ALARM GPIO_TIM16_CH1OUT_2
|
||||
|
||||
/* USB OTG FS */
|
||||
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 1 */
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
#define HRT_PPM_CHANNEL /* T3C2 */ 2 /* use capture/compare channel 2 */
|
||||
#define GPIO_PPM_IN /* PC7 T3C2 */ GPIO_TIM3_CH2IN_3
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_RSSI_IN /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
|
||||
|
||||
/* Safety Switch: Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PC4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
|
||||
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PA10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
|
||||
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFETY_BUTTON() */
|
||||
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
|
||||
|
||||
/* No PX4IO processor present */
|
||||
#define PX4_MFT_HW_SUPPORTED_PX4_MFT_PX4IO 0
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
|
||||
|
||||
/*
|
||||
* Board has a separate RC_IN
|
||||
*
|
||||
* GPIO PPM_IN on PB0 T3CH3
|
||||
* GPIO PPM_IN on PC7 T3CH2
|
||||
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
|
||||
* Inversion is possible in the UART and can drive GPIO_PPM_IN as an output
|
||||
*/
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
|
||||
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
|
||||
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
@@ -156,7 +172,7 @@
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
#define BOARD_NUM_IO_TIMERS 6
|
||||
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
@@ -171,9 +187,12 @@
|
||||
GPIO_CAN2_SILENT_S0, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
GPIO_LEVEL_SHIFTER_OE, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_OTGFS_VBUS, \
|
||||
GPIO_BTN_SAFETY, \
|
||||
GPIO_LED_SAFETY, \
|
||||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
@@ -35,6 +35,5 @@
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(3),
|
||||
initI2CBusExternal(4),
|
||||
};
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortG, GPIO::Pin3}, SPI::DRDY{GPIO::PortG, GPIO::Pin2}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin15}, SPI::DRDY{GPIO::PortE, GPIO::Pin12}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
@@ -46,7 +46,10 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI5, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin6}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin0}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortG, GPIO::Pin9}),
|
||||
}),
|
||||
};
|
||||
|
||||
|
||||
@@ -33,6 +33,28 @@
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
/* Timer allocation
|
||||
*
|
||||
* TIM1_CH4 T FMU_CH1
|
||||
* TIM1_CH3 T FMU_CH2
|
||||
* TIM1_CH2 T FMU_CH3
|
||||
* TIM1_CH1 T FMU_CH4
|
||||
*
|
||||
* TIM4_CH2 T FMU_CH5
|
||||
* TIM4_CH3 T FMU_CH6
|
||||
* TIM2_CH3 T FMU_CH7
|
||||
* TIM2_CH1 T FMU_CH8
|
||||
*
|
||||
* TIM2_CH4 T FMU_CH9
|
||||
* TIM15_CH1 T FMU_CH10
|
||||
*
|
||||
* TIM8_CH1 T FMU_CH11
|
||||
*
|
||||
* TIM4_CH4 T FMU_CH12
|
||||
*
|
||||
* TIM16_CH1 T BUZZER - Driven by other driver
|
||||
*/
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
@@ -56,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
|
||||
@@ -93,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
|
||||
@@ -110,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
|
||||
@@ -127,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
|
||||
|
||||
@@ -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=y
|
||||
|
||||
@@ -1,5 +0,0 @@
|
||||
CONFIG_EKF2_AUX_GLOBAL_POSITION=n
|
||||
CONFIG_EKF2_VERBOSE_STATUS=n
|
||||
CONFIG_MODULES_EKF2=n
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_BOARD_NOLOCKSTEP=y
|
||||
@@ -99,6 +99,7 @@ set(msg_files
|
||||
FollowTargetStatus.msg
|
||||
GeneratorStatus.msg
|
||||
GeofenceResult.msg
|
||||
GeofenceStatus.msg
|
||||
GimbalControls.msg
|
||||
GimbalDeviceAttitudeStatus.msg
|
||||
GimbalDeviceInformation.msg
|
||||
@@ -173,6 +174,7 @@ set(msg_files
|
||||
RegisterExtComponentReply.msg
|
||||
RegisterExtComponentRequest.msg
|
||||
Rpm.msg
|
||||
RtlStatus.msg
|
||||
RtlTimeEstimate.msg
|
||||
SatelliteInfo.msg
|
||||
SensorAccel.msg
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -0,0 +1,7 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint32 geofence_id # loaded geofence id
|
||||
uint8 status # Current geofence status
|
||||
|
||||
uint8 GF_STATUS_LOADING = 0
|
||||
uint8 GF_STATUS_READY = 1
|
||||
@@ -1,8 +1,8 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint16 mission_id # Id for the mission for which the result was generated
|
||||
uint16 geofence_id # Id for the corresponding geofence for which the result was generated (used for mission feasibility)
|
||||
uint64 home_position_counter # Counter of the home position for which the result was generated (used for mission feasibility)
|
||||
uint32 mission_id # Id for the mission for which the result was generated
|
||||
uint32 geofence_id # Id for the corresponding geofence for which the result was generated (used for mission feasibility)
|
||||
uint32 home_position_counter # Counter of the home position for which the result was generated (used for mission feasibility)
|
||||
|
||||
int32 seq_reached # Sequence of the mission item which has been reached, default -1
|
||||
uint16 seq_current # Sequence of the current mission item
|
||||
|
||||
@@ -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
|
||||
@@ -47,4 +47,4 @@ uint16 ADSB_EMITTER_TYPE_SERVICE_SURFACE=18
|
||||
uint16 ADSB_EMITTER_TYPE_POINT_OBSTACLE=19
|
||||
uint16 ADSB_EMITTER_TYPE_ENUM_END=20
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 8
|
||||
uint8 ORB_QUEUE_LENGTH = 16
|
||||
|
||||
@@ -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_size(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 size of a topic
|
||||
* @param meta orb topic metadata
|
||||
*/
|
||||
extern uint8_t orb_get_queue_size(const struct orb_metadata *meta);
|
||||
|
||||
/**
|
||||
* Print a topic to console. Do not call this directly, use print_message() instead.
|
||||
* @param meta orb topic metadata
|
||||
|
||||
@@ -48,37 +48,10 @@
|
||||
|
||||
static uORB::SubscriptionInterval *filp_to_subscription(cdev::file_t *filp) { return static_cast<uORB::SubscriptionInterval *>(filp->f_priv); }
|
||||
|
||||
// round up to nearest power of two
|
||||
// Such as 0 => 1, 1 => 1, 2 => 2 ,3 => 4, 10 => 16, 60 => 64, 65...255 => 128
|
||||
// Note: When the input value > 128, the output is always 128
|
||||
static inline uint8_t round_pow_of_two_8(uint8_t n)
|
||||
{
|
||||
if (n == 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Avoid is already a power of 2
|
||||
uint8_t value = n - 1;
|
||||
|
||||
// Fill 1
|
||||
value |= value >> 1U;
|
||||
value |= value >> 2U;
|
||||
value |= value >> 4U;
|
||||
|
||||
// Unable to round-up, take the value of round-down
|
||||
if (value == UINT8_MAX) {
|
||||
value >>= 1U;
|
||||
}
|
||||
|
||||
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 +159,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 +190,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 +227,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 +355,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 +448,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_get_queue_size(ORB_ID(orb_test_medium_wrap_around));
|
||||
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_get_queue_size(ORB_ID(orb_test_medium_queue));
|
||||
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_get_queue_size(ORB_ID(orb_test_medium_queue_poll));
|
||||
|
||||
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) {
|
||||
|
||||
@@ -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()
|
||||
|
||||
@@ -160,6 +160,11 @@ status_t Argus_InitMode(argus_hnd_t *hnd, s2pi_slave_t spi_slave, argus_mode_t m
|
||||
* Also refer to #Argus_ReinitMode, which uses a specified measurement
|
||||
* mode instead of the currently active measurement mode.
|
||||
*
|
||||
* @note If a full re-initialization is not desired, refer to the
|
||||
* #Argus_RestoreDeviceState function that will only re-write the
|
||||
* register map to the device to restore its state after an power
|
||||
* cycle.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
*
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
@@ -182,6 +187,11 @@ status_t Argus_Reinit(argus_hnd_t *hnd);
|
||||
* Also refer to #Argus_Reinit, which re-uses the currently active
|
||||
* measurement mode instead of an user specified measurement mode.
|
||||
*
|
||||
* @note If a full re-initialization is not desired, refer to the
|
||||
* #Argus_RestoreDeviceState function that will only re-write the
|
||||
* register map to the device to restore its state after an power
|
||||
* cycle.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
*
|
||||
* @param mode The specified measurement mode to be initialized.
|
||||
@@ -274,6 +284,69 @@ argus_hnd_t *Argus_CreateHandle(void);
|
||||
*****************************************************************************/
|
||||
status_t Argus_DestroyHandle(argus_hnd_t *hnd);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Restores the device state with a re-write of all register values.
|
||||
*
|
||||
* @details The function invalidates and restores the device state by executing
|
||||
* a re-write of the full register map.
|
||||
*
|
||||
* The purpose of this function is to recover from known external
|
||||
* events like power cycles, for example due to sleep / wake-up
|
||||
* functionality. This can be implemented by cutting off the external
|
||||
* power supply of the device (e.g. via a MOSFET switch controlled by
|
||||
* a GPIB pin). By calling this function, the expected state of the
|
||||
* API is written to the device without the need to fully re-initialize
|
||||
* the device. Thus, the API can resume where it has stopped as if
|
||||
* there has never been a power cycle.
|
||||
*
|
||||
* The internal state machines like the dynamic configuration adaption
|
||||
* (DCA) algorithm will not be reseted. The API/sensor will immediately
|
||||
* resume at the last state that was optimized for the given
|
||||
* environmental conditions.
|
||||
*
|
||||
* The use case of sleep / wake-up can be implemented as follows:
|
||||
*
|
||||
* 1. In case of ongoing measurements, stop the measurements via
|
||||
* the #Argus_StopMeasurementTimer function (if started by the
|
||||
* #Argus_StartMeasurementTimer function).
|
||||
*
|
||||
* 2. Shut down the device by removing the 5V power supply, e.g.
|
||||
* via a GPIO pin that switches a MOSFET circuit.
|
||||
*
|
||||
* 3. After the desired sleep period, power the device by switching
|
||||
* the 5V power supply on again. Wait until the power-on-reset
|
||||
* (POR) is finished (approx. 1 ms) or just repeat step 4 until
|
||||
* it succeeds.
|
||||
*
|
||||
* 4. Call the #Argus_RestoreDeviceState function to trigger the
|
||||
* restoration of the device state in the API. Note that the
|
||||
* function will return an error code if it fails. One can repeat
|
||||
* the execution of that function a few times until it succeeds.
|
||||
*
|
||||
* 6. Continue with measurements via #Argus_StartMeasurementTimer
|
||||
* of #Argus_TriggerMeasurement functions as desired.
|
||||
*
|
||||
* @note If a complete re-initialization (= soft-reset) is desired, see
|
||||
* the #Argus_Reinit functionality.
|
||||
*
|
||||
* @note Changing a configuration or calibration parameter will always
|
||||
* invalidate the device state as well as the state machine of the
|
||||
* dynamic configuration adaption (DCA) algorithm. In that case, the
|
||||
* device/API needs a few measurements to adopt to the present
|
||||
* environmental conditions before the first valid measurement result
|
||||
* can be obtained. This is almost similar to re-initializing the
|
||||
* device (see #Argus_Reinit) which would also re-read the EEPROM.
|
||||
* On the other hand, the #Argus_RestoreDeviceState does not reset
|
||||
* or re-initialize anything. It just makes sure that the device
|
||||
* register map (which has changed to its reset values after the
|
||||
* power cycle) is what the API expects upon the next measurement.
|
||||
*
|
||||
* @param hnd The device handle object to be invalidated.
|
||||
*
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_RestoreDeviceState(argus_hnd_t *hnd);
|
||||
|
||||
/*!**************************************************************************
|
||||
* Generic API
|
||||
****************************************************************************/
|
||||
@@ -726,7 +799,7 @@ status_t Argus_ExecuteXtalkCalibrationSequence(argus_hnd_t *hnd);
|
||||
* After calibration has finished successfully, the obtained data is
|
||||
* applied immediately and can be read from the API using the
|
||||
* #Argus_GetCalibrationPixelRangeOffsets or
|
||||
* #Argus_GetCalibrationGlobalRangeOffset function.
|
||||
* #Argus_GetCalibrationGlobalRangeOffsets function.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
@@ -775,7 +848,7 @@ status_t Argus_ExecuteRelativeRangeOffsetCalibrationSequence(argus_hnd_t *hnd);
|
||||
* After calibration has finished successfully, the obtained data is
|
||||
* applied immediately and can be read from the API using the
|
||||
* #Argus_GetCalibrationPixelRangeOffsets or
|
||||
* #Argus_GetCalibrationGlobalRangeOffset function.
|
||||
* #Argus_GetCalibrationGlobalRangeOffsets function.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param targetRange The absolute range between the reference plane and the
|
||||
@@ -1043,28 +1116,40 @@ status_t Argus_GetConfigurationUnambiguousRange(argus_hnd_t *hnd,
|
||||
****************************************************************************/
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Sets the global range offset value to a specified device.
|
||||
* @brief Sets the global range offset values to a specified device.
|
||||
*
|
||||
* @details The global range offset is subtracted from the raw range values.
|
||||
* @details The global range offsets are subtracted from the raw range values.
|
||||
* There are two distinct values that are applied in low or high
|
||||
* power stage setting respectively.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param value The new global range offset in meter and Q0.15 format.
|
||||
* @param offset_low The new global range offset for the low power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @param offset_high The new global range offset for the high power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_SetCalibrationGlobalRangeOffset(argus_hnd_t *hnd,
|
||||
q0_15_t value);
|
||||
status_t Argus_SetCalibrationGlobalRangeOffsets(argus_hnd_t *hnd,
|
||||
q0_15_t offset_low,
|
||||
q0_15_t offset_high);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Gets the global range offset value from a specified device.
|
||||
* @brief Gets the global range offset values from a specified device.
|
||||
*
|
||||
* @details The global range offset is subtracted from the raw range values.
|
||||
* @details The global range offsets are subtracted from the raw range values.
|
||||
* There are two distinct values that are applied in low or high
|
||||
* power stage setting respectively.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param value The current global range offset in meter and Q0.15 format.
|
||||
* @param offset_low The current range offset for the low power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @param offset_high The current global range offset for the high power stage
|
||||
* in meter and Q0.15 format.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_GetCalibrationGlobalRangeOffset(argus_hnd_t *hnd,
|
||||
q0_15_t *value);
|
||||
status_t Argus_GetCalibrationGlobalRangeOffsets(argus_hnd_t *hnd,
|
||||
q0_15_t *offset_low,
|
||||
q0_15_t *offset_high);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Sets the relative pixel offset table to a specified device.
|
||||
|
||||
@@ -210,9 +210,13 @@ typedef enum argus_dca_gain_t {
|
||||
* - [9]: #ARGUS_STATE_LASER_ERROR
|
||||
* - [10]: #ARGUS_STATE_HAS_DATA
|
||||
* - [11]: #ARGUS_STATE_HAS_AUX_DATA
|
||||
* - [12]: #ARGUS_STATE_DCA_MAX
|
||||
* - [12]: #ARGUS_STATE_SATURATED_PIXELS
|
||||
* - [13]: DCA Power Stage
|
||||
* - [14-15]: DCA Gain Stages
|
||||
* - [16]: #ARGUS_STATE_DCA_MIN
|
||||
* - [17]: #ARGUS_STATE_DCA_MAX
|
||||
* - [18]: #ARGUS_STATE_DCA_RESET
|
||||
* - [18-31]: not used
|
||||
* .
|
||||
*****************************************************************************/
|
||||
typedef enum argus_state_t {
|
||||
@@ -229,36 +233,35 @@ typedef enum argus_state_t {
|
||||
* - 1: Enabled: measurement with detuned frequency. */
|
||||
ARGUS_STATE_DUAL_FREQ_MODE = 1U << 1U,
|
||||
|
||||
/*! 0x0004: Measurement Frequency for Dual Frequency Mode
|
||||
/*! 0x0004: Measurement Frequency for Dual Frequency Mode \n
|
||||
* (only if #ARGUS_STATE_DUAL_FREQ_MODE flag is set).
|
||||
* - 0: A-Frame w/ detuned frequency,
|
||||
* - 1: B-Frame w/ detuned frequency */
|
||||
ARGUS_STATE_MEASUREMENT_FREQ = 1U << 2U,
|
||||
|
||||
/*! 0x0008: Debug Mode. If set, the range value of erroneous pixels
|
||||
/*! 0x0008: Debug Mode. \n
|
||||
* If set, the range value of erroneous pixels
|
||||
* are not cleared or reset.
|
||||
* - 0: Disabled (default).
|
||||
* - 1: Enabled. */
|
||||
ARGUS_STATE_DEBUG_MODE = 1U << 3U,
|
||||
|
||||
/*! 0x0010: Weak Signal Flag.
|
||||
/*! 0x0010: Weak Signal Flag. \n
|
||||
* Set whenever the Pixel Binning Algorithm is detecting a
|
||||
* weak signal, i.e. if the amplitude dies not reach its
|
||||
* (absolute) threshold. If the Golden Pixel is enabled,
|
||||
* this also indicates that the Pixel Binning Algorithm
|
||||
* falls back to the Golden Pixel.
|
||||
* (absolute) threshold.
|
||||
* - 0: Normal Signal.
|
||||
* - 1: Weak Signal or Golden Pixel Mode. */
|
||||
* - 1: Weak Signal. */
|
||||
ARGUS_STATE_WEAK_SIGNAL = 1U << 4U,
|
||||
|
||||
/*! 0x0020: Background Light Warning Flag.
|
||||
/*! 0x0020: Background Light Warning Flag. \n
|
||||
* Set whenever the background light is very high and the
|
||||
* measurement data might be unreliable.
|
||||
* - 0: No Warning: Background Light is within valid range.
|
||||
* - 1: Warning: Background Light is very high. */
|
||||
ARGUS_STATE_BGL_WARNING = 1U << 5U,
|
||||
|
||||
/*! 0x0040: Background Light Error Flag.
|
||||
/*! 0x0040: Background Light Error Flag. \n
|
||||
* Set whenever the background light is too high and the
|
||||
* measurement data is unreliable or invalid.
|
||||
* - 0: No Error: Background Light is within valid range.
|
||||
@@ -270,7 +273,7 @@ typedef enum argus_state_t {
|
||||
* - 1: PLL locked at start of integration. */
|
||||
ARGUS_STATE_PLL_LOCKED = 1U << 7U,
|
||||
|
||||
/*! 0x0100: Laser Failure Warning Flag.
|
||||
/*! 0x0100: Laser Failure Warning Flag. \n
|
||||
* Set whenever the an invalid system condition is detected.
|
||||
* (i.e. DCA at max state but no amplitude on any (incl. reference)
|
||||
* pixel, not amplitude but any saturated pixel).
|
||||
@@ -279,7 +282,7 @@ typedef enum argus_state_t {
|
||||
* condition stays, a laser malfunction error is raised. */
|
||||
ARGUS_STATE_LASER_WARNING = 1U << 8U,
|
||||
|
||||
/*! 0x0200: Laser Failure Error Flag.
|
||||
/*! 0x0200: Laser Failure Error Flag. \n
|
||||
* Set whenever a laser malfunction error is raised and the
|
||||
* system is put into a safe state.
|
||||
* - 0: No Error: Laser is operating properly.
|
||||
@@ -297,13 +300,12 @@ typedef enum argus_state_t {
|
||||
* - 1: Auxiliary data is available and correctly evaluated. */
|
||||
ARGUS_STATE_HAS_AUX_DATA = 1U << 11U,
|
||||
|
||||
/*! 0x1000: DCA Maximum State Flag.
|
||||
* Set whenever the DCA has extended all its parameters to their
|
||||
* maximum values and can not increase the integration energy any
|
||||
* further.
|
||||
* - 0: DCA has not yet reached its maximum state.
|
||||
* - 1: DCA has reached its maximum state and can not increase any further. */
|
||||
ARGUS_STATE_DCA_MAX = 1U << 12U,
|
||||
/*! 0x0100: Pixel Saturation Flag. \n
|
||||
* Set whenever any pixel is saturated, i.e. its pixel state is
|
||||
* #PIXEL_SAT
|
||||
* - 0: No saturated pixels.
|
||||
* - 1: Any saturated pixels. */
|
||||
ARGUS_STATE_SATURATED_PIXELS = 1U << 12U,
|
||||
|
||||
/*! 0x2000: DCA is in high Optical Output Power stage. */
|
||||
ARGUS_STATE_DCA_POWER_HIGH = DCA_POWER_HIGH << ARGUS_STATE_DCA_POWER_SHIFT,
|
||||
@@ -320,6 +322,31 @@ typedef enum argus_state_t {
|
||||
/*! 0xC000: DCA is in high Pixel Input Gain stage. */
|
||||
ARGUS_STATE_DCA_GAIN_HIGH = DCA_GAIN_HIGH << ARGUS_STATE_DCA_GAIN_SHIFT,
|
||||
|
||||
/*! 0x10000: DCA Minimum State Flag. \n
|
||||
* Set whenever the DCA has reduced all its parameters to their
|
||||
* minimum values and it can not decrease the integration energy
|
||||
* any further.
|
||||
* - 0: DCA has not yet reached its minimum state.
|
||||
* - 1: DCA has reached its minimum state and can not decrease
|
||||
* its parameters any further. */
|
||||
ARGUS_STATE_DCA_MIN = 1U << 16U,
|
||||
|
||||
/*! 0x20000: DCA Maximum State Flag. \n
|
||||
* Set whenever the DCA has extended all its parameters to their
|
||||
* maximum values and it can not increase the integration energy
|
||||
* any further.
|
||||
* - 0: DCA has not yet reached its maximum state.
|
||||
* - 1: DCA has reached its maximum state and can not increase
|
||||
* its parameters any further. */
|
||||
ARGUS_STATE_DCA_MAX = 1U << 17U,
|
||||
|
||||
/*! 0x20000: DCA Reset State Flag. \n
|
||||
* Set whenever the DCA is resetting all its parameters to their
|
||||
* minimum values because it has detected too many saturated pixels.
|
||||
* - 0: DCA is operating in normal mode.
|
||||
* - 1: DCA is performing a reset. */
|
||||
ARGUS_STATE_DCA_RESET = 1U << 18U,
|
||||
|
||||
} argus_state_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
|
||||
@@ -58,6 +58,7 @@ extern "C" {
|
||||
*****************************************************************************/
|
||||
|
||||
#include "utility/int_math.h"
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
|
||||
|
||||
@@ -138,6 +139,13 @@ extern "C" {
|
||||
#define PIXEL_CH2N(c) (((((c) << 1U) ^ 0x1CU) & 0x1CU) | (((c) >> 3U) & 0x02U) | ((c) & 0x01U))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixels n-index.
|
||||
* @param n n-index of the pixel.
|
||||
* @return The pixel mask with only n-index pixel set.
|
||||
******************************************************************************/
|
||||
#define PIXELN_MASK(n) (0x01U << (n))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a pixel given by the n-index is enabled in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
@@ -151,16 +159,23 @@ extern "C" {
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param n n-index of the pixel to enable.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ENABLE(msk, n) ((msk) |= (0x01U << (n)))
|
||||
#define PIXELN_ENABLE(msk, n) ((msk) |= (PIXELN_MASK(n)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disable a pixel given by the n-index in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param n n-index of the pixel to disable.
|
||||
******************************************************************************/
|
||||
#define PIXELN_DISABLE(msk, n) ((msk) &= (~(0x01U << (n))))
|
||||
#define PIXELN_DISABLE(msk, n) ((msk) &= (~PIXELN_MASK(n)))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixels ADC channel number.
|
||||
* @param c The ADC channel number of the pixel.
|
||||
* @return The 32-bit pixel mask with only pixel ADC channel set.
|
||||
******************************************************************************/
|
||||
#define PIXELCH_MASK(c) (0x01U << (PIXEL_CH2N(c)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if an ADC pixel channel is enabled from a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
@@ -184,6 +199,14 @@ extern "C" {
|
||||
#define PIXELCH_DISABLE(msk, c) (PIXELN_DISABLE(msk, PIXEL_CH2N(c)))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixel x-y-indices.
|
||||
* @param x x-index of the pixel.
|
||||
* @param y y-index of the pixel.
|
||||
* @return The 32-bit pixel mask with only pixel ADC channel set.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_MASK(x, y) (0x01U << (PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a pixel given by the x-y-indices is enabled in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
@@ -337,10 +360,10 @@ static inline uint32_t ShiftSelectedPixels(const uint32_t pixel_mask,
|
||||
|
||||
uint32_t shifted_mask = 0;
|
||||
|
||||
for (uint8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (uint8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
int8_t x_src = x - dx;
|
||||
int8_t y_src = y - dy;
|
||||
for (int8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (int8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
int8_t x_src = (int8_t)(x - dx);
|
||||
int8_t y_src = (int8_t)(y - dy);
|
||||
|
||||
if (dy & 0x1) {
|
||||
/* Compensate for hexagonal pixel shape. */
|
||||
@@ -409,8 +432,8 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
int8_t min_y = -1;
|
||||
|
||||
/* Find nearest not selected pixel. */
|
||||
for (uint8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (uint8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
for (int8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (int8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
if (!PIXELXY_ISENABLED(pixel_mask, x, y)) {
|
||||
int32_t distx = (x - center_x) << 1;
|
||||
|
||||
@@ -423,8 +446,8 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
|
||||
if (dist < min_dist) {
|
||||
min_dist = dist;
|
||||
min_x = x;
|
||||
min_y = y;
|
||||
min_x = (int8_t)x;
|
||||
min_y = (int8_t)y;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -438,6 +461,64 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
|
||||
return pixel_mask;
|
||||
}
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Fills a pixel mask with the direct neighboring pixels around a pixel.
|
||||
*
|
||||
* @details The pixel mask is iteratively filled with the direct neighbors of the
|
||||
* specified center pixel.
|
||||
*
|
||||
* Note that the function is able to handle corner and edge pixels and
|
||||
* also to handle odd/even lines (which have different layouts)
|
||||
*
|
||||
* @param x The selected pixel x-index.
|
||||
* @param y The selected pixel y-index.
|
||||
* @return The filled pixel mask with all direct neighbors of the selected pixel.
|
||||
******************************************************************************/
|
||||
static inline uint32_t GetAdjacentPixelsMask(const uint_fast8_t x,
|
||||
const uint_fast8_t y)
|
||||
{
|
||||
assert(x < ARGUS_PIXELS_X);
|
||||
assert(y < ARGUS_PIXELS_Y);
|
||||
|
||||
uint32_t mask = 0u;
|
||||
|
||||
bool isXEdgeLow = (x == 0);
|
||||
bool isXEdgeHigh = (x == (ARGUS_PIXELS_X - 1));
|
||||
bool isYEdgeLow = (y == 0);
|
||||
bool isYEdgeHigh = (y == (ARGUS_PIXELS_Y - 1));
|
||||
|
||||
if (y % 2 == 0) {
|
||||
if (!isYEdgeLow) { PIXELXY_ENABLE(mask, x, y - 1); }
|
||||
|
||||
if ((!isXEdgeHigh) && (!isYEdgeLow)) { PIXELXY_ENABLE(mask, x + 1, y - 1); }
|
||||
|
||||
if (!isXEdgeHigh) { PIXELXY_ENABLE(mask, x + 1, y); }
|
||||
|
||||
if ((!isXEdgeHigh) && (!isYEdgeHigh)) { PIXELXY_ENABLE(mask, x + 1, y + 1); }
|
||||
|
||||
if (!isYEdgeHigh) { PIXELXY_ENABLE(mask, x, y + 1); }
|
||||
|
||||
if (!isXEdgeLow) { PIXELXY_ENABLE(mask, x - 1, y); }
|
||||
|
||||
} else {
|
||||
if ((!isXEdgeLow) && (!isYEdgeLow)) { PIXELXY_ENABLE(mask, x - 1, y - 1); }
|
||||
|
||||
if (!isYEdgeLow) { PIXELXY_ENABLE(mask, x, y - 1); }
|
||||
|
||||
if (!isXEdgeHigh) { PIXELXY_ENABLE(mask, x + 1, y); }
|
||||
|
||||
if (!isYEdgeHigh) { PIXELXY_ENABLE(mask, x, y + 1); }
|
||||
|
||||
if ((!isXEdgeLow) && (!isYEdgeHigh)) { PIXELXY_ENABLE(mask, x - 1, y + 1); }
|
||||
|
||||
if (!isXEdgeLow) { PIXELXY_ENABLE(mask, x - 1, y); }
|
||||
}
|
||||
|
||||
return mask;
|
||||
}
|
||||
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
|
||||
@@ -1,170 +0,0 @@
|
||||
/*************************************************************************//**
|
||||
* @file
|
||||
* @brief This file is part of the AFBR-S50 API.
|
||||
* @details Defines macros to work with pixel and ADC channel masks.
|
||||
*
|
||||
* @copyright
|
||||
*
|
||||
* Copyright (c) 2021, Broadcom Inc
|
||||
* 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 of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from
|
||||
* this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*****************************************************************************/
|
||||
|
||||
#ifndef ARGUS_MSK_H
|
||||
#define ARGUS_MSK_H
|
||||
|
||||
/*!***************************************************************************
|
||||
* @defgroup argusmap ADC Channel Mapping
|
||||
* @ingroup argusres
|
||||
*
|
||||
* @brief Pixel ADC Channel (n) to x-y-Index Mapping
|
||||
*
|
||||
* @details The ADC Channels of each pixel or auxiliary channel on the device
|
||||
* is numbered in a way that is convenient on the chip. The macros
|
||||
* in this module are defined in order to obtain the x-y-indices of
|
||||
* each channel and vice versa.
|
||||
*
|
||||
* @addtogroup argusmap
|
||||
* @{
|
||||
*****************************************************************************/
|
||||
|
||||
#include "api/argus_def.h"
|
||||
#include "utility/int_math.h"
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the channel number of an specified Pixel.
|
||||
* @param x The x index of the pixel.
|
||||
* @param y The y index of the pixel.
|
||||
* @return The channel number n of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_XY2N(x, y) ((((x) ^ 7) << 1) | ((y) & 2) << 3 | ((y) & 1))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the x index of an specified Pixel channel.
|
||||
* @param n The channel number of the pixel.
|
||||
* @return The x index number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_N2X(n) ((((n) >> 1U) & 7) ^ 7)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the y index of an specified Pixel channel.
|
||||
* @param n The channel number of the pixel.
|
||||
* @return The y index number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_N2Y(n) (((n) & 1U) | (((n) >> 3) & 2U))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC Pixel channel was enabled from a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
* @return True if the pixel channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ISENABLED(msk, ch) (((msk) >> (ch)) & 0x01U)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro enables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ENABLE(msk, ch) ((msk) |= (0x01U << (ch)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELN_DISABLE(msk, ch) ((msk) &= (~(0x01U << (ch))))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if an ADC Pixel channel was enabled from a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
* @return True if the pixel (x,y) was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_ISENABLED(msk, x, y) (PIXELN_ISENABLED(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro enables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_ENABLE(msk, x, y) (PIXELN_ENABLE(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_DISABLE(msk, x, y) (PIXELN_DISABLE(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_ISENABLED(msk, ch) (((msk) >> ((ch) - 32U)) & 0x01U)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_ENABLE(msk, ch) ((msk) |= (0x01U << ((ch) - 32U)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_DISABLE(msk, ch) ((msk) &= (~(0x01U << ((ch) - 32U))))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the number of enabled pixel channels via a popcount
|
||||
* algorithm.
|
||||
* @param pxmsk 32-bit pixel mask
|
||||
* @return The count of enabled pixel channels.
|
||||
******************************************************************************/
|
||||
#define PIXEL_COUNT(pxmsk) popcount(pxmsk)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the number of enabled channels via a popcount
|
||||
* algorithm.
|
||||
* @param pxmsk 32-bit pixel mask
|
||||
* @param chmsk 32-bit channel mask
|
||||
* @return The count of enabled ADC channels.
|
||||
******************************************************************************/
|
||||
#define CHANNEL_COUNT(pxmsk, chmsk) (popcount(pxmsk) + popcount(chmsk))
|
||||
|
||||
/*! @} */
|
||||
#endif /* ARGUS_MSK_H */
|
||||
@@ -36,6 +36,9 @@
|
||||
|
||||
#ifndef ARGUS_OFFSET_H
|
||||
#define ARGUS_OFFSET_H
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/*!***************************************************************************
|
||||
* @addtogroup argus_cal
|
||||
@@ -48,12 +51,26 @@
|
||||
* @brief Pixel Range Offset Table.
|
||||
* @details Contains pixel range offset values for all 32 active pixels.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_offset_table_t {
|
||||
/*! The offset values per pixel in meter and Q0.15 format. */
|
||||
q0_15_t Table[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
typedef union argus_cal_offset_table_t {
|
||||
struct {
|
||||
/*! The offset values table for Low Power Stage of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t LowPower[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
/*! The offset values table for High Power Stage of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t HighPower[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The offset values table for Low/High Power Stages of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t Table[ARGUS_DCA_POWER_STAGE_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
} argus_cal_offset_table_t;
|
||||
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
#endif /* ARGUS_OFFSET_T */
|
||||
|
||||
@@ -55,11 +55,11 @@ extern "C" {
|
||||
* information from the filtered pixels by averaging them in a
|
||||
* specified way.
|
||||
*
|
||||
* The Pixel Binning Algorithm is a three-stage filter with a
|
||||
* fallback value:
|
||||
* Basically, the Pixel Binning Algorithm is a multi-stage filter:
|
||||
*
|
||||
* -# A fixed pre-filter mask is applied to statically disable
|
||||
* specified pixels.
|
||||
*
|
||||
* -# A relative and absolute amplitude filter is applied in the
|
||||
* second stage. The relative filter is determined by a ratio
|
||||
* of the maximum amplitude off all available (i.e. not filtered
|
||||
@@ -75,12 +75,28 @@ extern "C" {
|
||||
* selected and considered for the final 1D distance. The
|
||||
* absolute threshold is used to dismiss pixels that are below
|
||||
* the noise level. The latter would be considered for the 1D
|
||||
* result if the maximum amplitude is already very low.
|
||||
* result if the maximum amplitude is already very low.\n
|
||||
* Those threshold are implemented using a hysteresis behavior.
|
||||
* For its configuration, see the following parameters:
|
||||
* - #argus_cfg_pba_t::RelativeAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::RelativeAmplitudeExclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteAmplitudeExclusion
|
||||
* .
|
||||
*
|
||||
* -# An absolute minimum distance filter is applied in addition
|
||||
* to the amplitude filter. This removes all pixel that have
|
||||
* a lower distance than the specified threshold. This is used
|
||||
* to remove invalid pixels that can be detected by a physically
|
||||
* not correct negative distance.
|
||||
* not correct negative distance.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_MIN_DIST_SCOPE
|
||||
* - #argus_cfg_pba_t::AbsoluteDistanceScopeInclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteDistanceScopeExclusion
|
||||
* - #argus_cfg_pba_t::RelativeDistanceScopeInclusion
|
||||
* - #argus_cfg_pba_t::RelativeDistanceScopeExclusion
|
||||
* .
|
||||
*
|
||||
* -# A distance filter is used to distinguish pixels that target
|
||||
* the actual object from pixels that see the brighter background,
|
||||
* e.g. white walls. Thus, the pixel with the minimum distance
|
||||
@@ -90,11 +106,31 @@ extern "C" {
|
||||
* determined by an relative (to the current minimum distance)
|
||||
* and an absolute value. The larger scope value is the
|
||||
* relevant one, i.e. the relative distance scope can be used
|
||||
* to heed the increasing noise at larger distances.
|
||||
* to heed the increasing noise at larger distances.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #argus_cfg_pba_t::AbsoluteMinimumDistanceThreshold
|
||||
* .
|
||||
*
|
||||
* -# If all of the above filters fail to determine a single valid
|
||||
* pixel, the Golden Pixel is used as a fallback value. The
|
||||
* Golden Pixel is the pixel that sits right at the focus point
|
||||
* of the optics at large distances.
|
||||
* of the optics at large distances. Thus, it is expected to
|
||||
* have the best signal at large distances.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_GOLDPX_FALLBACK_MODE
|
||||
* .
|
||||
*
|
||||
* -# In order to avoid unwanted effects from "out-of-focus" pixels
|
||||
* in application that require a smaller focus, the Golden Pixel
|
||||
* Priority Mode prioritizes a valid signal on the central
|
||||
* Golden Pixel over other pixels. That is, while the Golden
|
||||
* Pixel has a reasonable signal strength, it is the only pixel
|
||||
* considered for the 1D result.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_GOLDPX_FALLBACK_MODE
|
||||
* - #argus_cfg_pba_t::GoldenPixelPriorityAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::GoldenPixelPriorityAmplitudeExclusion
|
||||
* .
|
||||
* .
|
||||
*
|
||||
* After filtering is done, there may be more than a single pixel
|
||||
@@ -113,14 +149,17 @@ extern "C" {
|
||||
* @brief Enable flags for the pixel binning algorithm.
|
||||
*
|
||||
* @details Determines the pixel binning algorithm feature enable status.
|
||||
*
|
||||
* - [0]: #PBA_ENABLE: Enables the pixel binning feature.
|
||||
* - [1]: reserved
|
||||
* - [2]: reserved
|
||||
* - [3]: reserved
|
||||
* - [4]: reserved
|
||||
* - [5]: #PBA_ENABLE_GOLDPX: Enables the Golden Pixel feature.
|
||||
* - [6]: #PBA_ENABLE_MIN_DIST_SCOPE: Enables the minimum distance scope
|
||||
* feature.
|
||||
* - [4]: #PBA_ENABLE_GOLDPX_PRIORITY_MODE: Enables the Golden Pixel
|
||||
* priority mode feature.
|
||||
* - [5]: #PBA_ENABLE_GOLDPX_FALLBACK_MODE: Enables the Golden Pixel
|
||||
* fallback mode feature.
|
||||
* - [6]: #PBA_ENABLE_MIN_DIST_SCOPE: Enables the minimum distance
|
||||
* scope feature.
|
||||
* - [7]: reserved
|
||||
* .
|
||||
*****************************************************************************/
|
||||
@@ -128,8 +167,17 @@ typedef enum argus_pba_flags_t {
|
||||
/*! Enables the pixel binning feature. */
|
||||
PBA_ENABLE = 1U << 0U,
|
||||
|
||||
/*! Enables the Golden Pixel. */
|
||||
PBA_ENABLE_GOLDPX = 1U << 5U,
|
||||
/*! Enables the Golden Pixel Priority Mode.
|
||||
* If enabled, the Golden Pixel is prioritized over other Pixels as long
|
||||
* as it has a good signal (determined by # */
|
||||
PBA_ENABLE_GOLDPX_PRIORITY_MODE = 1U << 4U,
|
||||
|
||||
/*! Enables the Golden Pixel Fallback Mode.
|
||||
* If enabled, the Golden Pixel is used as a last fallback pixel to obtain
|
||||
* a valid signal from. This is recommended for all non-multi pixel
|
||||
* devices whose TX field-of-view is aligned to target the Golden Pixel in
|
||||
* factory calibration. */
|
||||
PBA_ENABLE_GOLDPX_FALLBACK_MODE = 1U << 5U,
|
||||
|
||||
/*! Enables the minimum distance scope filter. */
|
||||
PBA_ENABLE_MIN_DIST_SCOPE = 1U << 6U,
|
||||
@@ -168,65 +216,297 @@ typedef struct {
|
||||
* about the individual evaluation modes. */
|
||||
argus_pba_averaging_mode_t AveragingMode;
|
||||
|
||||
/*! The Relative amplitude threshold value (in %) of the max. amplitude.
|
||||
/*! The relative amplitude inclusion threshold (in %) of the max. amplitude.
|
||||
*
|
||||
* Pixels with amplitude below this threshold value are dismissed.
|
||||
* Pixels, whose amplitudes raise above this inclusion threshold, are
|
||||
* added to the pixel binning. The amplitude must fall below the
|
||||
* exclusion (#RelativeAmplitudeExclusion) threshold to be removed from
|
||||
* the pixel binning again.
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Use 0 to disable the relative amplitude threshold. */
|
||||
uq0_8_t RelAmplThreshold;
|
||||
|
||||
/*! The relative minimum distance scope value in %.
|
||||
* Note: in addition to the relative criteria, there is also the absolute
|
||||
* criteria (#AbsoluteAmplitudeInclusion, #AbsoluteAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Pixels that have a range value within [x0, x0 + dx] are considered
|
||||
* for the pixel binning, where x0 is the minimum distance of all
|
||||
* amplitude picked pixels and dx is the minimum distance scope value.
|
||||
* The minimum distance scope value will be the maximum of relative
|
||||
* and absolute value.
|
||||
* Must be greater than or equal to the #RelativeAmplitudeExclusion.
|
||||
*
|
||||
* Use #RelativeAmplitudeExclusion == #RelativeAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #RelativeAmplitudeExclusion and
|
||||
* #RelativeAmplitudeInclusion) to disable the relative amplitude
|
||||
* hysteresis. */
|
||||
uq0_8_t RelativeAmplitudeInclusion;
|
||||
|
||||
/*! The relative amplitude exclusion threshold (in %) of the max. amplitude.
|
||||
*
|
||||
* Pixels, whose amplitudes fall below this exclusion threshold, are
|
||||
* removed from the pixel binning. The amplitude must raise above the
|
||||
* inclusion (#RelativeAmplitudeInclusion) threshold to be added back
|
||||
* to be pixel binning again.
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Special values:
|
||||
* - 0: Use 0 for absolute value only or to choose the pixel with the
|
||||
* minimum distance only (of also the absolute value is 0)! */
|
||||
uq0_8_t RelMinDistanceScope;
|
||||
* Note: in addition to the relative criteria, there is also the absolute
|
||||
* criteria (#AbsoluteAmplitudeInclusion, #AbsoluteAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be less than or equal to #RelativeAmplitudeInclusion.
|
||||
*
|
||||
* Use #RelativeAmplitudeExclusion == #RelativeAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #RelativeAmplitudeExclusion and
|
||||
* #RelativeAmplitudeInclusion) to disable the relative amplitude
|
||||
* hysteresis. */
|
||||
uq0_8_t RelativeAmplitudeExclusion;
|
||||
|
||||
/*! The absolute amplitude threshold value in LSB.
|
||||
/*! The absolute amplitude inclusion threshold in LSB.
|
||||
*
|
||||
* Pixels with amplitude below this threshold value are dismissed.
|
||||
* Pixels, whose amplitudes raise above this inclusion threshold, are
|
||||
* added to the pixel binning. The amplitude must fall below the
|
||||
* exclusion (#RelativeAmplitudeExclusion) threshold to be removed from
|
||||
* the pixel binning again.
|
||||
*
|
||||
* The absolute amplitude threshold is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the threshold is set to 0 LSB internally.
|
||||
* The absolute amplitude hysteresis is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the thresholds are set to 0 LSB internally
|
||||
* which disables the absolute criteria.
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Use 0 to disable the absolute amplitude threshold. */
|
||||
uq12_4_t AbsAmplThreshold;
|
||||
|
||||
/*! The absolute minimum distance scope value in m.
|
||||
* Note: in addition to the absolute criteria, there is also the relative
|
||||
* criteria (#RelativeAmplitudeInclusion, #RelativeAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Pixels that have a range value within [x0, x0 + dx] are considered
|
||||
* for the pixel binning, where x0 is the minimum distance of all
|
||||
* amplitude picked pixels and dx is the minimum distance scope value.
|
||||
* The minimum distance scope value will be the maximum of relative
|
||||
* and absolute value.
|
||||
* Must be greater than or equal to #AbsoluteAmplitudeExclusion.
|
||||
*
|
||||
* Use #AbsoluteAmplitudeExclusion == #AbsoluteAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #AbsoluteAmplitudeExclusion and
|
||||
* #AbsoluteAmplitudeInclusion) to disable the absolute amplitude
|
||||
* hysteresis. */
|
||||
uq12_4_t AbsoluteAmplitudeInclusion;
|
||||
|
||||
/*! The absolute amplitude exclusion threshold in LSB.
|
||||
*
|
||||
* Pixels, whose amplitudes fall below this exclusion threshold, are
|
||||
* removed from the pixel binning. The amplitude must raise above the
|
||||
* inclusion (#RelativeAmplitudeInclusion) threshold to be added back
|
||||
* to be pixel binning again.
|
||||
*
|
||||
* The absolute amplitude hysteresis is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the thresholds are set to 0 LSB internally
|
||||
* which disables the absolute criteria.
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Note: in addition to the absolute criteria, there is also the relative
|
||||
* criteria (#RelativeAmplitudeInclusion, #RelativeAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be less than or equal to #AbsoluteAmplitudeInclusion.
|
||||
*
|
||||
* Use #AbsoluteAmplitudeExclusion == #AbsoluteAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #AbsoluteAmplitudeExclusion and
|
||||
* #AbsoluteAmplitudeInclusion) to disable the absolute amplitude
|
||||
* hysteresis. */
|
||||
uq12_4_t AbsoluteAmplitudeExclusion;
|
||||
|
||||
/*! The Golden Pixel Priority Mode inclusion threshold in LSB.
|
||||
*
|
||||
* The Golden Pixel Priority Mode prioritizes a valid signal on the
|
||||
* Golden Pixel over other pixel to avoid unwanted effects from
|
||||
* "out-of-focus" pixels in application that require a smaller focus.
|
||||
*
|
||||
* If the Golden Pixel priority mode is enabled (see
|
||||
* #PBA_ENABLE_GOLDPX_PRIORITY_MODE) and the Golden Pixel has a valid signal
|
||||
* with amplitude higher than this inclusion threshold, its priority state
|
||||
* is enabled and the binning exits early by dismissing all other pixels
|
||||
* regardless of their respective amplitude or state. The Golden Pixel
|
||||
* priority state is disabled if the Golden Pixel amplitude falls below
|
||||
* the exclusion threshold (#GoldenPixelPriorityAmplitudeExclusion) or its
|
||||
* state becomes invalid (e.g. #PIXEL_SAT).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel priority mode hysteresis. */
|
||||
uq12_4_t GoldenPixelPriorityAmplitudeInclusion;
|
||||
|
||||
/*! The Golden Pixel Priority Mode exclusion threshold in LSB.
|
||||
*
|
||||
* The Golden Pixel Priority Mode prioritizes a valid signal on the
|
||||
* Golden Pixel over other pixel to avoid unwanted effects from
|
||||
* "out-of-focus" pixels in application that require a smaller focus.
|
||||
*
|
||||
* If the Golden Pixel priority mode is enabled (see
|
||||
* #PBA_ENABLE_GOLDPX_PRIORITY_MODE) and the Golden Pixel has a valid
|
||||
* signal with amplitude higher than the exclusion threshold
|
||||
* (#GoldenPixelPriorityAmplitudeInclusion), its priority state is enabled
|
||||
* and the binning exits early by dismissing all other pixels regardless
|
||||
* of their respective amplitude or state. The Golden Pixel priority state
|
||||
* is disabled if the Golden Pixel amplitude falls below this exclusion
|
||||
* threshold or its state becomes invalid (e.g. #PIXEL_SAT).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel priority mode hysteresis. */
|
||||
uq12_4_t GoldenPixelPriorityAmplitudeExclusion;
|
||||
|
||||
/*! The relative minimum distance scope inclusion threshold (in %).
|
||||
*
|
||||
* Pixels, whose range is smaller than the minimum distance inclusion
|
||||
* threshold (x_min + dx_incl) are added to the pixel binning. The
|
||||
* range must raise above the exclusion
|
||||
* (#RelativeDistanceScopeExclusion) threshold to be removed
|
||||
* from the pixel binning again. The relative value is determined
|
||||
* by multiplying the percentage with the minimum distance.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute inclusion values
|
||||
* (#AbsoluteDistanceScopeInclusion).
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Must be smaller than or equal to the #RelativeDistanceScopeExclusion.
|
||||
*
|
||||
* Use #RelativeDistanceScopeExclusion == #RelativeDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq0_8_t RelativeDistanceScopeInclusion;
|
||||
|
||||
/*! The relative distance scope exclusion threshold (in %).
|
||||
*
|
||||
* Pixels, whose range is larger than the minimum distance exclusion
|
||||
* threshold (x_min + dx_excl) are removed from the pixel binning. The
|
||||
* range must fall below the inclusion
|
||||
* (#RelativeDistanceScopeInclusion) threshold to be added
|
||||
* to the pixel binning again. The relative value is determined
|
||||
* by multiplying the percentage with the minimum distance.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#AbsoluteDistanceScopeExclusion).
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Must be larger than or equal to the #RelativeDistanceScopeInclusion.
|
||||
*
|
||||
* Use #RelativeDistanceScopeExclusion == #RelativeDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq0_8_t RelativeDistanceScopeExclusion;
|
||||
|
||||
/*! The absolute minimum distance scope inclusion threshold (in m).
|
||||
*
|
||||
* Pixels, whose range is smaller than the minimum distance inclusion
|
||||
* threshold (x_min + dx_incl) are added to the pixel binning. The
|
||||
* range must raise above the exclusion
|
||||
* (#AbsoluteDistanceScopeExclusion) threshold to be added
|
||||
* to the pixel binning again.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#RelativeDistanceScopeInclusion).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/2^15.
|
||||
*
|
||||
* Special values:
|
||||
* - 0: Use 0 for relative value only or to choose the pixel with the
|
||||
* minimum distance only (of also the relative value is 0)! */
|
||||
uq1_15_t AbsMinDistanceScope;
|
||||
* Must be smaller than or equal to the #AbsoluteDistanceScopeExclusion.
|
||||
*
|
||||
* Use #AbsoluteDistanceScopeExclusion == #AbsoluteDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq1_15_t AbsoluteDistanceScopeInclusion;
|
||||
|
||||
/*! The absolute minimum distance scope exclusion threshold (in m).
|
||||
*
|
||||
* Pixels, whose range is larger than the minimum distance exclusion
|
||||
* threshold (x_min + dx_excl) are removed from the pixel binning. The
|
||||
* range must fall below the inclusion
|
||||
* (#AbsoluteDistanceScopeInclusion) threshold to be added
|
||||
* to the pixel binning again.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#RelativeDistanceScopeExclusion).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/2^15.
|
||||
*
|
||||
* Must be larger than or equal to the #AbsoluteDistanceScopeInclusion.
|
||||
*
|
||||
* Use #AbsoluteDistanceScopeExclusion == #AbsoluteDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq1_15_t AbsoluteDistanceScopeExclusion;
|
||||
|
||||
/*! The Golden Pixel Saturation Filter Pixel Threshold.
|
||||
*
|
||||
* The Golden Pixel Saturation Filter will evaluate the status of the
|
||||
* Golden Pixel to #PIXEL_INVALID if a certain number of active pixels,
|
||||
* i.e. pixels that are not removed by the static pre-filter mask
|
||||
* (#PrefilterMask), are saturated (#PIXEL_SAT).
|
||||
*
|
||||
* The purpose of this filter is to avoid erroneous situations with highly
|
||||
* reflective targets (e.g. retro-reflectors) that can invalidate the
|
||||
* Golden Pixel such that it would not show the correct saturation state.
|
||||
* In order to avoid using the Golden Pixel in that scenario, this filter
|
||||
* mechanism can be used to remove the Golden Pixel if a specified number
|
||||
* of other pixels show saturation state.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel Saturation Filter. */
|
||||
uint8_t GoldenPixelSaturationFilterPixelThreshold;
|
||||
|
||||
/*! The Golden Pixel out-of-sync age limit for the GPPM.
|
||||
*
|
||||
* The Golden Pixel out-of-sync age is the number of consecutive frames
|
||||
* where the Golden Pixel is out-of-sync. This parameters is the threshold
|
||||
* to distinguish between temporary and permanent out-of-sync states.
|
||||
*
|
||||
* Temporary out-of-sync states happen when the target rapidly changes. In
|
||||
* this case, the Golden Pixel Priority Mode (GPPM) is not exited. Only if
|
||||
* the out-of-sync age exceeds the specified threshold, the Golden Pixel is
|
||||
* considered erroneous and the GPPM is exited.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel out-of-sync aging (= infinity). */
|
||||
uint8_t GoldenPixelOutOfSyncAgeThreshold;
|
||||
|
||||
/*! The absolute minimum distance threshold value in m.
|
||||
*
|
||||
* Pixels with distance below this threshold value are dismissed. */
|
||||
q9_22_t AbsMinDistanceThreshold;
|
||||
q9_22_t AbsoluteMinimumDistanceThreshold;
|
||||
|
||||
/*! The pre-filter pixel mask determines the pixel channels that are
|
||||
* statically excluded from the pixel binning (i.e. 1D distance) result.
|
||||
|
||||
@@ -55,6 +55,9 @@ extern "C" {
|
||||
* Also used as a special value to determine no object detected or infinity range. */
|
||||
#define ARGUS_RANGE_MAX (Q9_22_MAX)
|
||||
|
||||
/*! Minimum range value in Q9.22 format. */
|
||||
#define ARGUS_RANGE_MIN (Q9_22_MIN)
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Status flags for the evaluated pixel structure.
|
||||
*
|
||||
|
||||
@@ -227,12 +227,19 @@ enum Status {
|
||||
|
||||
/*! -114: AFBR-S50 Error: Register data integrity is lost (e.g. due to unexpected
|
||||
* power-on-reset cycle or invalid write cycle of SPI. System tries to
|
||||
* reset the values. */
|
||||
* reset the values.
|
||||
*
|
||||
* @note If this error occurs after intentionally cycling the power supply
|
||||
* of the device, use the #Argus_RestoreDeviceState API function to properly
|
||||
* recover the current API state into the device to avoid that issue. */
|
||||
ERROR_ARGUS_DATA_INTEGRITY_LOST = -114,
|
||||
|
||||
/*! -115: AFBR-S50 Error: The range offsets calibration failed! */
|
||||
ERROR_ARGUS_RANGE_OFFSET_CALIBRATION_FAILED = -115,
|
||||
|
||||
/*! -116: AFBR-S50 Error: The VSUB calibration failed! */
|
||||
ERROR_ARGUS_VSUB_CALIBRATION_FAILED = -116,
|
||||
|
||||
/*! -191: AFBR-S50 Error: The device is currently busy and cannot execute the
|
||||
* requested command. */
|
||||
ERROR_ARGUS_BUSY = -191,
|
||||
|
||||
@@ -56,13 +56,13 @@ extern "C" {
|
||||
#define ARGUS_API_VERSION_MAJOR 1
|
||||
|
||||
/*! Minor version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_MINOR 4
|
||||
#define ARGUS_API_VERSION_MINOR 5
|
||||
|
||||
/*! Bugfix version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_BUGFIX 4
|
||||
#define ARGUS_API_VERSION_BUGFIX 6
|
||||
|
||||
/*! Build version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_BUILD "20230327150535"
|
||||
#define ARGUS_API_VERSION_BUILD "20240208081753"
|
||||
|
||||
/*****************************************************************************/
|
||||
|
||||
|
||||
@@ -72,30 +72,28 @@ typedef struct xtalk_t {
|
||||
* @details Contains crosstalk vector values for all 32 active pixels,
|
||||
* separated for A/B-Frames.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_xtalk_table_t {
|
||||
union {
|
||||
struct {
|
||||
/*! The crosstalk vector table for A-Frames. */
|
||||
xtalk_t FrameA[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
typedef union argus_cal_xtalk_table_t {
|
||||
struct {
|
||||
/*! The crosstalk vector table for A-Frames. */
|
||||
xtalk_t FrameA[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
/*! The crosstalk vector table for B-Frames. */
|
||||
xtalk_t FrameB[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The crosstalk vector table for A/B-Frames of all 32 pixels.*/
|
||||
xtalk_t Table[ARGUS_DFM_FRAME_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
/*! The crosstalk vector table for B-Frames. */
|
||||
xtalk_t FrameB[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The crosstalk vector table for A/B-Frames of all 32 pixels.*/
|
||||
xtalk_t Table[ARGUS_DFM_FRAME_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
} argus_cal_xtalk_table_t;
|
||||
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the pixel-to-pixel
|
||||
* crosstalk compensation feature.
|
||||
* @brief Electrical Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the electrical
|
||||
* pixel-to-pixel crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_p2pxtalk_t {
|
||||
/*! Pixel-To-Pixel Compensation on/off. */
|
||||
typedef struct argus_cal_electrical_p2pxtalk_t {
|
||||
/*! Electrical Pixel-To-Pixel Compensation on/off. */
|
||||
bool Enabled;
|
||||
|
||||
/*! The relative threshold determines when the compensation is active for
|
||||
@@ -134,8 +132,39 @@ typedef struct argus_cal_p2pxtalk_t {
|
||||
* Higher values determine more influence on the reference pixel signal. */
|
||||
q3_12_t KcFactorCRefPx;
|
||||
|
||||
} argus_cal_p2pxtalk_t;
|
||||
} argus_cal_electrical_p2pxtalk_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Optical Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the optical
|
||||
* pixel-to-pixel crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_optical_p2pxtalk_t {
|
||||
/*! Optical Pixel-To-Pixel Compensation on/off. */
|
||||
bool Enabled;
|
||||
|
||||
/*! The sine component of the coupling coefficient that determines the amount
|
||||
* of a neighbour pixel signal that influences the raw signal of certain pixel.
|
||||
* Higher values determine more influence on the individual pixel signal. */
|
||||
q3_12_t CouplingCoeffS;
|
||||
|
||||
/*! The cosine component of the coupling coefficient that determines the amount
|
||||
* of a neighbour pixel signal that influences the raw signal of a certain pixel.
|
||||
* Higher values determine more influence on the individual pixel signal. */
|
||||
q3_12_t CouplingCoeffC;
|
||||
|
||||
} argus_cal_optical_p2pxtalk_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains combined calibration data for electrical and
|
||||
* optical pixel-to-pixel crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_p2pxtalk_t {
|
||||
argus_cal_electrical_p2pxtalk_t Electrical;
|
||||
|
||||
argus_cal_optical_p2pxtalk_t Optical;
|
||||
} argus_cal_p2pxtalk_t;
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -61,7 +61,7 @@ extern "C" {
|
||||
* @details Algorithm to evaluate a/b, where b is in Q15.16 format, on a 32-bit
|
||||
* architecture with maximum precision.
|
||||
* The result is correctly rounded and given as the input format.
|
||||
* Division by 0 yields max. values determined by signa of numerator.
|
||||
* Division by 0 yields max. values determined by signs of numerator.
|
||||
* Too high/low results are truncated to max/min values.
|
||||
*
|
||||
* Depending on the architecture, the division is implemented with a 64-bit
|
||||
@@ -89,14 +89,14 @@ inline int32_t fp_div16(int32_t a, q15_16_t b)
|
||||
|
||||
if (c > 0x80000000U) { return INT32_MIN; }
|
||||
|
||||
return -c;
|
||||
return (int32_t) - c;
|
||||
|
||||
} else {
|
||||
c = ((c / b) + (1 << 13U)) >> 14U;
|
||||
|
||||
if (c > (int64_t)INT32_MAX) { return INT32_MAX; }
|
||||
|
||||
return c;
|
||||
return (int32_t)c;
|
||||
}
|
||||
|
||||
#else
|
||||
@@ -159,10 +159,16 @@ inline int32_t fp_div16(int32_t a, q15_16_t b)
|
||||
|
||||
/* Figure out the sign of result */
|
||||
if ((uint32_t)(a ^ b) & 0x80000000U) {
|
||||
result = -result;
|
||||
return (int32_t) - result;
|
||||
|
||||
} else {
|
||||
// fix 05.10.2023; the corner case, when result == INT32_MAX + 1:
|
||||
// Catch the wraparound (to INT32_MIN) and truncate instead.
|
||||
if (quotient > INT32_MAX) { return INT32_MAX; }
|
||||
|
||||
return (int32_t)result;
|
||||
}
|
||||
|
||||
return (int32_t)result;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -118,7 +118,7 @@ inline uint32_t fp_mulu(uint32_t u, uint32_t v, uint_fast8_t shift)
|
||||
assert(shift <= 32);
|
||||
#if USE_64BIT_MUL
|
||||
const uint64_t w = (uint64_t)u * (uint64_t)v;
|
||||
return (w >> shift) + ((w >> (shift - 1)) & 1U);
|
||||
return (uint32_t)((w >> shift) + ((w >> (shift - 1)) & 1U));
|
||||
#else
|
||||
uint32_t tmp[2] = { 0 };
|
||||
muldwu(tmp, u, v);
|
||||
@@ -158,15 +158,15 @@ inline int32_t fp_muls(int32_t u, int32_t v, uint_fast8_t shift)
|
||||
|
||||
uint32_t u2, v2;
|
||||
|
||||
if (u < 0) { u2 = -u; sign = -sign; } else { u2 = u; }
|
||||
if (u < 0) { u2 = (uint32_t) - u; sign = -sign; } else { u2 = (uint32_t)u; }
|
||||
|
||||
if (v < 0) { v2 = -v; sign = -sign; } else { v2 = v; }
|
||||
if (v < 0) { v2 = (uint32_t) - v; sign = -sign; } else { v2 = (uint32_t)v; }
|
||||
|
||||
const uint32_t res = fp_mulu(u2, v2, shift);
|
||||
|
||||
assert(sign > 0 ? res <= 0x7FFFFFFFU : res <= 0x80000000U);
|
||||
|
||||
return sign > 0 ? res : -res;
|
||||
return sign > 0 ? (int32_t)res : -(int32_t)res;
|
||||
}
|
||||
|
||||
|
||||
@@ -225,7 +225,9 @@ inline uint32_t fp_mul_u32_u16(uint32_t u, uint16_t v, uint_fast8_t shift)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_mul_s32_u16(int32_t u, uint16_t v, uint_fast8_t shift)
|
||||
{
|
||||
return u >= 0 ? fp_mul_u32_u16(u, v, shift) : - fp_mul_u32_u16(-u, v, shift);
|
||||
return u >= 0 ?
|
||||
(int32_t)fp_mul_u32_u16((uint32_t)u, v, shift) :
|
||||
-(int32_t)fp_mul_u32_u16((uint32_t) - u, v, shift);
|
||||
}
|
||||
|
||||
/*! @} */
|
||||
|
||||
@@ -80,7 +80,7 @@ inline uint32_t fp_rndu(uint32_t Q, uint_fast8_t n)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_rnds(int32_t Q, uint_fast8_t n)
|
||||
{
|
||||
return (Q < 0) ? -fp_rndu(-Q, n) : fp_rndu(Q, n);
|
||||
return (Q < 0) ? -(int32_t)fp_rndu((uint32_t)(-Q), n) : (int32_t)fp_rndu((uint32_t)Q, n);
|
||||
}
|
||||
|
||||
/*!***************************************************************************
|
||||
@@ -108,7 +108,7 @@ inline uint32_t fp_truncu(uint32_t Q, uint_fast8_t n)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_truncs(int32_t Q, uint_fast8_t n)
|
||||
{
|
||||
return (Q < 0) ? -fp_truncu(-Q, n) : fp_truncu(Q, n);
|
||||
return (Q < 0) ? -(int32_t)fp_truncu((uint32_t)(-Q), n) : (int32_t)fp_truncu((uint32_t)Q, n);
|
||||
}
|
||||
|
||||
/*! @} */
|
||||
|
||||
@@ -66,7 +66,7 @@ inline uint32_t log2i(uint32_t x)
|
||||
{
|
||||
assert(x != 0);
|
||||
#if 1
|
||||
return 31 - __builtin_clz(x);
|
||||
return (uint32_t)(31 - __builtin_clz(x));
|
||||
#else
|
||||
#define S(k) if (x >= (1 << k)) { i += k; x >>= k; }
|
||||
int i = 0; S(16); S(8); S(4); S(2); S(1); return i;
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -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 */
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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");
|
||||
|
||||
@@ -14,7 +14,7 @@ class XMLInject():
|
||||
def __init__(self, injected_xml_filename):
|
||||
self.groups=[]
|
||||
|
||||
valid_parameter_attributes = set(["category", "default", "name", "type", "volatile"])
|
||||
valid_parameter_attributes = set(["category", "default", "name", "type", "volatile", "boolean"])
|
||||
valid_field_tags = set(["board","short_desc", "long_desc", "min", "max", "unit", "decimal", "increment", "reboot_required"])
|
||||
valid_other_top_level_tags = set(["group","values"])
|
||||
|
||||
@@ -42,7 +42,8 @@ class XMLInject():
|
||||
new_param.default = iparam.get('default')
|
||||
elif param_attrib == 'volatile':
|
||||
new_param.SetVolatile()
|
||||
|
||||
elif param_attrib == "boolean":
|
||||
new_param.SetBoolean()
|
||||
|
||||
#get param info stored as child tags
|
||||
for child in iparam:
|
||||
|
||||
@@ -73,6 +73,6 @@ __EXPORT void mavlink_vasprintf(int severity, orb_advert_t *mavlink_log_pub, con
|
||||
orb_publish(ORB_ID(mavlink_log), *mavlink_log_pub, &log_msg);
|
||||
|
||||
} else {
|
||||
*mavlink_log_pub = orb_advertise_queue(ORB_ID(mavlink_log), &log_msg, mavlink_log_s::ORB_QUEUE_LENGTH);
|
||||
*mavlink_log_pub = orb_advertise(ORB_ID(mavlink_log), &log_msg);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -156,18 +156,18 @@ private:
|
||||
#ifndef CONSTRAINED_FLASH
|
||||
&_external_checks,
|
||||
#endif
|
||||
//&_accelerometer_checks,
|
||||
//&_airspeed_checks,
|
||||
&_accelerometer_checks,
|
||||
&_airspeed_checks,
|
||||
&_arm_permission_checks,
|
||||
//&_baro_checks,
|
||||
&_baro_checks,
|
||||
&_cpu_resource_checks,
|
||||
&_distance_sensor_checks,
|
||||
&_esc_checks,
|
||||
&_estimator_checks,
|
||||
&_failure_detector_checks,
|
||||
//&_gyro_checks,
|
||||
//&_imu_consistency_checks,
|
||||
//&_magnetometer_checks,
|
||||
&_gyro_checks,
|
||||
&_imu_consistency_checks,
|
||||
&_magnetometer_checks,
|
||||
&_manual_control_checks,
|
||||
&_home_position_checks,
|
||||
&_mission_checks,
|
||||
|
||||
@@ -55,7 +55,7 @@ public:
|
||||
void SetUp() override
|
||||
{
|
||||
// ensure topic exists, otherwise we might lose first queued events
|
||||
orb_advertise_queue(ORB_ID(event), nullptr, event_s::ORB_QUEUE_LENGTH);
|
||||
orb_advertise(ORB_ID(event), nullptr);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
@@ -99,7 +99,7 @@ void EstimatorChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
}
|
||||
}
|
||||
|
||||
if (missing_data && _param_sys_mc_est_group.get() == 2 && false) {
|
||||
if (missing_data && _param_sys_mc_est_group.get() == 2) {
|
||||
/* EVENT
|
||||
*/
|
||||
reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate,
|
||||
|
||||
@@ -153,7 +153,7 @@ int buzzer_init()
|
||||
tune_durations[tune_control_s::TUNE_ID_BATTERY_WARNING_SLOW] = 800000;
|
||||
tune_durations[tune_control_s::TUNE_ID_SINGLE_BEEP] = 300000;
|
||||
|
||||
tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control, tune_control_s::ORB_QUEUE_LENGTH);
|
||||
tune_control_pub = orb_advertise(ORB_ID(tune_control), &tune_control);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
@@ -330,7 +330,7 @@ int led_init()
|
||||
led_control.mode = led_control_s::MODE_OFF;
|
||||
led_control.priority = 0;
|
||||
led_control.timestamp = hrt_absolute_time();
|
||||
led_control_pub = orb_advertise_queue(ORB_ID(led_control), &led_control, led_control_s::ORB_QUEUE_LENGTH);
|
||||
led_control_pub = orb_advertise(ORB_ID(led_control), &led_control);
|
||||
|
||||
/* first open normal LEDs */
|
||||
fd_leds = px4_open(LED0_DEVICE_PATH, O_RDWR);
|
||||
|
||||
@@ -1006,8 +1006,8 @@ int do_mag_calibration_quick(orb_advert_t *mavlink_log_pub, float heading_radian
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
calibration_log_critical(mavlink_log_pub, "Assuming vehicle is facing heading %.1f degrees",
|
||||
(double)math::radians(heading_radians));
|
||||
calibration_log_info(mavlink_log_pub, "Assuming vehicle is facing heading %.1f degrees",
|
||||
(double)math::degrees(heading_radians));
|
||||
|
||||
matrix::Eulerf euler{matrix::Quatf{attitude.q}};
|
||||
euler(2) = heading_radians;
|
||||
|
||||
@@ -52,7 +52,7 @@ parameters:
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0.3
|
||||
default: 50.0
|
||||
RDD_P_HEADING:
|
||||
description:
|
||||
short: Proportional gain for heading controller
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user