Compare commits

...

75 Commits

Author SHA1 Message Date
Hamish Willee d74af6d1f8 Delete simpleapp CMakeLists 2021-10-18 08:33:52 +11:00
Alex Klimaj b482986e8e uavcannode: Add CANNODE_TERM parameter (configure CAN termination on ARK cannodes)
- adds functionality to enable the built in can termination on the ARK cannodes
2021-10-15 09:29:56 -04:00
Jari van Ewijk 55910caec5 UCANS32K146: Enable CONFIG_BCH to use EEEPROM as character driver 2021-10-15 05:54:27 -07:00
Silvan Fuhrer a66b0829b0 Standard VTOL: add airspeed to back transition logic and refactor it a bit
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-15 09:58:48 +02:00
Silvan Fuhrer 358c67226e Tiltrotor: backtransition logic improvements
-use groundspeed in body x for exit condition
-use airspeed for speed exit condition if no valid groundspeed

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-15 09:58:48 +02:00
Silvan Fuhrer cba80a6338 Tiltrotor: front transition: fade out yaw equally to roll
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-15 09:58:48 +02:00
Silvan Fuhrer 641383cbfb VTOL backtransition improvements
* vtol_type: only allow positive pitch setpoints during backtransition

* vtol params: set default of VT_B_DEC_FF to 0, as for most frames a FF is not necessary

* Tiltrotor: fix throttle during first part of back transition

* Tiltrotor: only enable all motors in second phase of backtransition (tilting phase)

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-15 09:58:48 +02:00
RomanBapst af291e2040 FlightTaskTransition: Transition improvements
- use fw pitch setpoint offset during transition
- take over previous vertical velocity and smooth out over transition

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-10-15 09:58:48 +02:00
Silvan Fuhrer d39c32619e Tiltrotor: add minimum throttle of 0.25 during front transition
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-15 09:58:48 +02:00
RomanBapst f61853d428 vtol: implement throttle blending out and into transition
- blend into TECS throttle after front transition
- blend out of TECS throttle during backtransition

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-10-15 09:58:48 +02:00
RomanBapst 8dd76050e0 vtol: take fixed wing attitude setpoint during transition if altitude is
not controlled

- required as there is no flightask running if altitude is not controlled

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-10-15 09:58:48 +02:00
Daniel Agar 435e5515df github actions: increase nuttx and linux ccache max size to 100M 2021-10-14 19:45:29 -04:00
Daniel Agar 7e71b7eafc github actions: compile nuttx archive bin files and remove duplicate nuttx cannode builds 2021-10-14 19:45:29 -04:00
Daniel Agar 12c7056ae5 drivers/imu: icm20602/icm20649/icm20948 remove timestamp_sample adjustments 2021-10-14 16:37:11 -04:00
Daniel Agar 56823b5ac9 ekf2: EKF control don't allow invalid flow gyro to propagate 2021-10-14 16:31:22 -04:00
Daniel Agar e8a064af02 github actions: try increasing nuttx ccache limit 2021-10-14 11:54:19 -04:00
Daniel Agar b88c8eb245 Jenkins: hardware stop commander before sensors module to avoid errors
- this is only done to silence timeouts during small benchmarks
2021-10-14 09:17:50 -04:00
Daniel Agar d35cf78e4a commander: PX4_ERR if attitude or angular velocity become invalid 2021-10-14 09:17:50 -04:00
Daniel Agar 4559230de6 drivers/imu/invensense: adjust icm20602/icm20649/icm20948 rescheduling logic
- this handles the case where the driver might be more than one full
transfer cycle behind
2021-10-14 09:17:11 -04:00
Daniel Agar ef4d4c3093 sensors/vehicle_imu: fix timestamp_sample increasing check 2021-10-14 09:12:45 -04:00
Jaeyoung-Lim 4535b18a80 Set setpoint type as const 2021-10-14 11:18:02 +02:00
Jaeyoung-Lim 07d72f8604 Fix comments 2021-10-14 11:18:02 +02:00
Jaeyoung-Lim 443666199e Move setmode outside of control_position
This commit moves the position controller mode handling outside of the control_position method.

The control_method is renamed to control_auto
2021-10-14 11:18:02 +02:00
Jaeyoung-Lim ae9e91f90c FW Pos controller: fix format in new switch
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-14 11:18:02 +02:00
Silvan Fuhrer c3e961a1ed FW Pos C: move setting of control_mode_current to separate function and minor clean ups
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-14 11:18:02 +02:00
Silvan Fuhrer 0cf3ef87e3 FW Position Controller: move nav_speed_2d calculation to function
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-14 11:18:02 +02:00
Jaeyoung-Lim 581ec224be Encapsulate loiter and position setpoint handling
This commit encapsulates the position setpoint and loiter setpoint handling into a single method, in order to make the code easier to understand
4be452
2021-10-14 11:18:02 +02:00
Thomas Debrunner f08f2a340d motion_planning: In VelovitySmoothing, mark const functions const 2021-10-13 21:25:43 -04:00
Thomas Debrunner fed234de81 flight_mode_manager: Extracted position trajectory motion planning into a library
Extract the functionality to plan smooth position motion trajectories into a
motion planning library, such that it can be used in other parts of the code as well.
2021-10-13 21:25:43 -04:00
Peter van der Perk 07303af8f8 UAVCANv1 Fix typo in #define 2021-10-13 21:22:15 -04:00
Peter van der Perk ed394027b1 UAVCANv1 Include Kconfig & Fix #18396 2021-10-13 21:22:15 -04:00
mcsauder a732ddaefb Deprecate 4250_teal from CMakeLists.txt. 2021-10-13 17:25:18 -04:00
mcsauder c1b0d78077 Minimize flash by migrating MIXER quad_x and PWM_OUT 1234 to rc.mc_defaults. Deprecate 4250_teal config file. 2021-10-13 17:25:18 -04:00
Matthias Grob 8b37db7825 Functions: fix corner case x_low == x_high == value resulting in NAN
and added unit test to cover it
2021-10-13 17:24:16 -04:00
alexklimaj f5e1da5b0f Fix broadcom afbrs50 build 2021-10-13 17:22:26 -04:00
Daniel Agar 7de00469a6 platforms: nuttx px4_init fix USB serial mavlink autodetect 2021-10-13 16:34:45 -04:00
Julian Oes f91aa76645 boards: add v5x RTPS version again
I just copied this from v5 and removed the heater.
2021-10-13 16:20:43 -04:00
David Lechner 426efb515f setup: fix installing in virtual env on Ubuntu
This fixes running the Ubuntu setup script in a Python virtual
environment. This was failing because pip doesn't allow the --user
option in virtual environments.
2021-10-13 16:19:24 -04:00
Jukka Laitinen 351f679c2f parameters: Use px4::atomic_bool instead of px4::atomic<bool>
This enables us to define the actual atomic bool type in px4_platform

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-10-13 15:01:26 -04:00
Jukka Laitinen e6658547cf sensors/vehicle_imu: Fix compiler warning for implicit INFINITY double->float cast
This pops up on some newer compilers

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-10-13 15:01:26 -04:00
Jukka Laitinen 5509235517 commander: Fix implicit NaN conversion from double to float compiler warning
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-10-13 15:01:26 -04:00
Daniel Agar 41a4045630 boards: nxp_fmuk66 fix serial_dma_poll 2021-10-13 13:45:39 -04:00
Daniel Agar 49a4283d0d boards: px4_fmu-v5x restore rc.board_mavlink
- this was unintentionally removed in https://github.com/PX4/PX4-Autopilot/pull/16180
2021-10-13 17:34:20 +02:00
alexklimaj ffb47466df Add ARK GPS passthrough 2021-10-12 22:00:58 -04:00
Mathieu Bresciani 56b0c46444 ekf2: improve optical flow angular rate compensation 2021-10-12 13:17:29 -04:00
Daniel Agar fab053d33b mavlink: receiver battery_status prevent out of bounds access
- fixes https://github.com/PX4/PX4-Autopilot/issues/18385
2021-10-12 09:20:40 -04:00
Daniel Agar 12670b70f4 Jenkins: hardware quick cal skip sleeps 2021-10-11 15:21:43 -04:00
Silvan Fuhrer 801ef2d520 VTOL main: add local variable for int(vehicle_command.param1 + 0.5)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-11 18:15:18 +02:00
Silvan Fuhrer 342e9900f8 vtol main: only guard against transition to FW in certain flight modes, never to MC
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2021-10-11 18:15:18 +02:00
SalimTerryLi 5ebe41efbf pilotpi: fix upload cmake 2021-10-11 10:43:59 -04:00
RomanBapst 8f8304f31e FixedWingPositionController: Set l1 variables to NAN if no l1 guidance
took place

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-10-11 16:41:42 +02:00
RomanBapst ae5d3103f4 fw l1 controller: added a flag to indicate if navigation has updated
- can be used to check if l1 controller ran during a cycle

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2021-10-11 16:41:42 +02:00
Jaeyoung-Lim e2f048f608 Add sitl glider model
Add airframe configs for SITL glider model

This commit adds an airframe config for a glider model
2021-10-10 12:33:25 -04:00
Shubham Shah 99b098f608 Update FixedwingAttitudeControl.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah c92cd65831 Update EKF2.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah 6576e1fda9 Update battery_status.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah b56bd7cb21 Update AirspeedValidator.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah 47a72a6b7b Update vtol_att_control_main.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah 9fd19a2c83 Update standard.cpp 2021-10-09 19:39:43 -04:00
Shubham Shah af34b21ba8 Update tiltrotor.cpp 2021-10-09 19:39:43 -04:00
Jacob Dahl 98f655815a mavlink: add LAND_TARGET stream 2021-10-09 10:29:02 -04:00
Daniel Agar 4be45229bf fw_pos_control_l1: fix launch detector dt update
- fixes https://github.com/PX4/PX4-Autopilot/issues/18354
2021-10-08 17:34:14 -04:00
Daniel Agar 089f96f800 lib/drivers/{accelerometer,gyroscope} skip obselete Vector3f construction
- FIFO clip count only check if value is INT16_MIN/MAX rather than abs() call
2021-10-08 17:33:27 -04:00
Jacob Dahl fd39d5b9a1 drivers/distance_sensor/lightware_laser_serial: add LW20/C support 2021-10-08 17:30:41 -04:00
Igor Mišić 47dc2ae5a5 Revert "protocol_splitter: delete non rtps or mavlink data from buffer"
This reverts commit 0cae3c129d.
2021-10-08 14:35:12 -04:00
alexklimaj 2ba369dd54 Add uavcannode fix2 mode and submode 2021-10-08 11:00:37 -04:00
Peter van der Perk d8e88aedc6 motor_ramp ram cleanup 2021-10-08 10:51:06 -04:00
Nicolas Martin ba66f8a1e2 reset hover thrust value in controllers when disarmed
During landing, hover thrust value can be very incorrect so it should be
reset before taking off
2021-10-08 10:39:49 +02:00
bresch ba1b7f3a07 CA pseudo inverse: set all small elements in CA matrix to zero
This avoids problems in the sequencial desaturation method where vectors
of the CA matrix are used to desaturate the motors.
2021-10-08 09:35:40 +02:00
bresch d1a2d6e1aa h480_ctrlalloc: tune rate controller 2021-10-08 09:35:40 +02:00
bresch 984a698760 matrix: update to include min/max of slices 2021-10-08 09:35:40 +02:00
bresch 21b1f090e6 SITL: add typhoon_h480_ctrlalloc target 2021-10-08 09:35:40 +02:00
bresch b18b7e84d2 CA pseudo-inverse: normalize control allocation matrix 2021-10-08 09:35:40 +02:00
bresch 927c0c4296 McRateControl: publish torque and thrust setpoint for control allocator 2021-10-08 09:35:40 +02:00
bresch 212df95193 ctrlalloc: use normal rate controller 2021-10-08 09:35:40 +02:00
163 changed files with 2936 additions and 1558 deletions
+20 -5
View File
@@ -734,12 +734,26 @@ void checkoutSCM() {
}
void quickCalibrate() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 1; param show CAL_ACC*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 1; param show CAL_GYRO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 1; param show SENS_BOARD*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 1; param show CAL_MAG*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_*"' // parameters before
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status || true"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_ACC*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_GYRO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SENS*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_MAG*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_*"' // parameters after
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
}
void checkStatus() {
@@ -831,6 +845,7 @@ void runTests() {
//sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_stress"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander stop"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors stop"' // ignore irrelevant sensor timeouts during microbenchmarks
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "microbench all"'
+1
View File
@@ -82,6 +82,7 @@ Checks: '*,
-modernize-use-equals-delete,
-modernize-use-override,
-modernize-use-using,
-modernize-use-trailing-return-type,
-performance-inefficient-string-concatenation,
-readability-avoid-const-params-in-decls,
-readability-container-size-empty,
+1 -1
View File
@@ -43,7 +43,7 @@ jobs:
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = 40M" >> ~/.ccache/ccache.conf
echo "max_size = 100M" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
ccache -s
ccache -z
+1 -1
View File
@@ -40,7 +40,7 @@ jobs:
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = 40M" >> ~/.ccache/ccache.conf
echo "max_size = 100M" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
ccache -s
ccache -z
+4 -2
View File
@@ -81,7 +81,7 @@ jobs:
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = 50M" >> ~/.ccache/ccache.conf
echo "max_size = 100M" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
ccache -s
ccache -z
@@ -110,4 +110,6 @@ jobs:
uses: actions/upload-artifact@v2
with:
name: px4_package_${{matrix.config}}
path: build/**/*.px4
path: |
build/**/*.px4
build/**/*.bin
@@ -1,64 +0,0 @@
name: NuttX UAVCAN firmware
on:
push:
branches:
- 'master'
pull_request:
branches:
- '*'
jobs:
build:
runs-on: ubuntu-latest
container: px4io/px4-dev-nuttx-focal:2021-09-08
strategy:
matrix:
config: [
ark_can-flow_default,
ark_can-gps_default,
ark_can-rtk-gps_default,
cuav_can-gps-v1_default,
freefly_can-rtk-gps_default,
holybro_can-gps-v1_default,
nxp_ucans32k146_default
]
steps:
- uses: actions/checkout@v1
with:
token: ${{secrets.ACCESS_TOKEN}}
- name: Prepare ccache timestamp
id: ccache_cache_timestamp
shell: cmake -P {0}
run: |
string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC)
message("::set-output name=timestamp::${current_date}")
- name: ccache cache files
uses: actions/cache@v2
with:
path: ~/.ccache
key: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
restore-keys: ${{matrix.config}}-ccache-
- name: setup ccache
run: |
mkdir -p ~/.ccache
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = 20M" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
ccache -s
ccache -z
- name: make ${{matrix.config}}
run: make ${{matrix.config}}
- name: ccache post-run
run: ccache -s
- name: Upload px4 package
uses: actions/upload-artifact@v2
with:
name: px4_cannode_${{matrix.config}}
path: build/${{matrix.config}}/*.uavcan.bin
@@ -0,0 +1,10 @@
#!/bin/sh
#
# @name Plane SITL with catapult
#
. ${R}etc/init.d-posix/airframes/1030_plane
param set-default FW_THR_CRUISE 0.0
param set-default RWTO_TKOFF 0
@@ -8,6 +8,15 @@
. ${R}etc/init.d/rc.mc_defaults
. ${R}etc/init.d/rc.ctrlalloc
param set-default MC_PITCHRATE_P 0.0800
param set-default MC_PITCHRATE_I 0.0400
param set-default MC_PITCHRATE_D 0.0010
param set-default MC_PITCH_P 9.0
param set-default MC_ROLLRATE_P 0.0800
param set-default MC_ROLLRATE_I 0.0400
param set-default MC_ROLLRATE_D 0.0010
param set-default MC_ROLL_P 9.0
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_P_ACC 3
@@ -61,6 +61,7 @@ px4_add_romfs_files(
1035_techpod
1036_malolo
1037_believer
1038_glider
1040_standard_vtol
1041_tailsitter
1042_tiltrotor
@@ -76,6 +77,6 @@ px4_add_romfs_files(
2507_cloudship
6011_typhoon_h480
6011_typhoon_h480.post
6012_typhoon_ctrlalloc
6012_typhoon_ctrlalloc.post
6012_typhoon_h480_ctrlalloc
6012_typhoon_h480_ctrlalloc.post
)
@@ -18,7 +18,6 @@
. ${R}etc/init.d/rc.fw_defaults
param set-default BAT1_N_CELLS 3
param set-default FW_AIRSPD_MAX 20
@@ -40,7 +39,6 @@ param set-default FW_RR_P 0.3
param set-default RWTO_TKOFF 1
param set SYS_HITL 1
# disable some checks to allow to fly
@@ -34,5 +34,3 @@ param set-default MC_PITCHRATE_D 0.0025
param set-default MC_YAWRATE_P 0.28
set MIXER quad_w
set PWM_OUT 1234
@@ -23,7 +23,6 @@
. ${R}etc/init.d/rc.mc_defaults
# TODO tune roll/pitch separately
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
@@ -39,5 +38,3 @@ param set-default BAT1_V_DIV 12.27559
param set-default BAT1_A_PER_V 15.39103
set MIXER quad_w
set PWM_OUT 1234
@@ -25,7 +25,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 4
param set-default MC_ROLL_P 7
@@ -38,5 +37,3 @@ param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.004
param set-default MC_YAW_P 4
set MIXER quad_w
set PWM_OUT 1234
@@ -25,7 +25,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 6
param set-default BAT1_V_EMPTY 3.5
@@ -42,5 +41,3 @@ param set-default MPC_XY_VEL_MAX 2
param set-default PWM_MAIN_MIN 1080
set MIXER quad_w
set PWM_OUT 1234
@@ -12,7 +12,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set SYS_HITL 1
@@ -22,11 +22,11 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default PWM_MAIN_MAX 2000
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 0
set MAV_TYPE 20
set MIXER quad_+_vtol
@@ -23,10 +23,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default PWM_AUX_DIS5 950
param set-default MC_ROLL_P 6
param set-default MC_ROLLRATE_P 0.17
param set-default MC_ROLLRATE_I 0.002
@@ -26,7 +26,6 @@ param set-default MC_ROLLRATE_I 0.01
param set-default MC_PITCHRATE_I 0.01
param set-default MC_YAW_P 3.5
param set-default MC_YAWRATE_MAX 50
param set-default MPC_XY_P 0.8
@@ -13,7 +13,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default FW_AIRSPD_MAX 22
param set-default FW_AIRSPD_MIN 14
param set-default FW_AIRSPD_TRIM 16
@@ -68,7 +67,6 @@ param set-default PWM_AUX_REV4 1
param set-default PWM_AUX_DIS5 950
param set-default VT_ARSP_TRANS 15
param set-default VT_F_TRANS_THR 0.6
param set-default VT_IDLE_PWM_MC 1180
@@ -13,7 +13,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default PWM_AUX_DISARM 1000
param set-default PWM_AUX_MAX 2000
param set-default PWM_AUX_MIN 1000
@@ -22,7 +22,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default CBRK_AIRSPD_CHK 162128
param set-default FW_ARSP_MODE 1
@@ -22,7 +22,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default BAT1_CAPACITY 23000
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.0025
@@ -22,7 +22,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default BAT1_N_CELLS 6
param set-default FW_AIRSPD_MAX 30
@@ -26,8 +26,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default VT_IDLE_PWM_MC 1100
param set-default VT_TYPE 1
param set-default VT_MOT_ID 1234
@@ -25,7 +25,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default PWM_AUX_DIS5 950
param set-default VT_TYPE 2
@@ -18,7 +18,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_COUNT 2
param set-default VT_TYPE 0
@@ -19,5 +19,3 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER tri_y_yaw+
set PWM_OUT 1234
@@ -19,5 +19,3 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER tri_y_yaw-
set PWM_OUT 1234
@@ -19,7 +19,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER coax
param set-default MC_ROLLRATE_P 0.17
param set-default MC_ROLLRATE_I 0.05
param set-default MC_ROLLRATE_D 0.005
@@ -41,5 +40,4 @@ param set-default RTL_DESCEND_ALT 10
set MIXER_AUX pass
# use PWM parameters for throttle channel
set PWM_AUX_OUT 1234
set PWM_OUT 34
@@ -24,8 +24,7 @@ set MAV_TYPE 4
set MIXER blade130
#set PWM_OUT 1234
set PWM_OUT none
param set-default ATT_BIAS_MAX 0
@@ -15,7 +15,6 @@
. ${R}etc/init.d/rc.balloon_defaults
param set-default COM_PREARM_MODE 2 # always in prearm state
param set-default CBRK_IO_SAFETY 22027
param set-default SDLOG_PROFILE 17
@@ -28,6 +27,5 @@ param set-default SER_TEL2_BAUD 9600
set MAV_TYPE 8
param set MAV_TYPE ${MAV_TYPE}
set MIXER IO_pass
set MIXER_AUX pass
@@ -28,7 +28,6 @@
set VEHICLE_TYPE mc
param set-default NAV_ACC_RAD 2
param set-default PWM_AUX_RATE 400
@@ -18,6 +18,5 @@
param set-default COM_PREARM_MODE 2
param set-default CBRK_IO_SAFETY 22027
set MIXER cloudship
set PWM_OUT 1234
@@ -37,5 +37,4 @@ param set-default FW_PR_FF 0.35
param set-default FW_RR_FF 0.6
param set-default FW_RR_P 0.04
set MIXER fw_generic_wing
@@ -41,7 +41,6 @@ param set-default FW_RR_P 0.04
param set-default PWM_MAIN_DISARM 1000
# Configure this as plane.
set MAV_TYPE 1
@@ -21,7 +21,6 @@
. ${R}etc/init.d/rc.fw_defaults
param set-default FW_AIRSPD_MAX 25
param set-default FW_AIRSPD_MIN 12.5
param set-default FW_AIRSPD_TRIM 16.5
@@ -21,7 +21,3 @@
#
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLL_P 8
param set-default MC_ROLLRATE_P 0.08
param set-default MC_ROLLRATE_I 0.16
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default ATT_BIAS_MAX 0
param set-default CBRK_IO_SAFETY 22027
@@ -11,9 +11,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
@@ -10,9 +10,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLLRATE_P 0.18
param set-default MC_PITCHRATE_P 0.18
param set-default MC_ROLLRATE_I 0.15
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default IMU_GYRO_CUTOFF 30
param set-default MC_ROLLRATE_P 0.14
@@ -16,10 +16,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
# System parameters
# use FMU motor outputs for less delay in the rate control loop
param set-default SYS_USE_IO 0
@@ -18,9 +18,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default IMU_DGYRO_CUTOFF 20
param set-default MC_ROLLRATE_P 0.18
@@ -13,6 +13,7 @@
. ${R}etc/init.d/rc.mc_defaults
. ${R}etc/init.d/rc.ctrlalloc
set MIXER none
param set-default MPC_USE_HTE 0
@@ -50,7 +51,5 @@ param set-default CA_MC_R3_CT 6.5
param set-default CA_MC_R3_KM -0.05
set MIXER direct
set PWM_OUT 1234
set MIXER_AUX direct_aux
set PWM_AUX_OUT 1234
@@ -18,7 +18,6 @@
. ${R}etc/init.d/rc.mc_defaults
# tuning
param set-default MC_PITCHRATE_P 0.11
param set-default MC_ROLLRATE_P 0.11
@@ -83,7 +82,5 @@ param set-default RC5_TRIM 1500
param set-default MAV_0_RATE 80000
param set-default MAV_0_MODE 2
param set-default SER_TEL1_BAUD 921600
set MIXER quad_x
set PWM_OUT 1234
set MIXER_AUX none
@@ -13,9 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLLRATE_P 0.14
param set-default MC_ROLLRATE_I 0.1
param set-default MC_ROLLRATE_D 0.004
@@ -42,8 +42,4 @@ param set-default RTL_DESCEND_ALT 10
set MIXER quad_h
set PWM_OUT 1234
set MIXER_AUX pass
set PWM_AUX_OUT 1234
@@ -23,7 +23,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default CBRK_SUPPLY_CHK 894281
param set-default CBRK_USB_CHK 197848
@@ -57,5 +56,3 @@ param set-default SYS_HAS_MAG 0
param set-default BAT1_N_CELLS 2
# The Whoop uses reversed props
set MIXER quad_h
set PWM_OUT 1234
@@ -12,10 +12,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_ROLL_P 8
param set-default MC_ROLLRATE_P 0.08
param set-default MC_ROLLRATE_I 0.25
@@ -23,11 +23,9 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_s250aq
set MAV_TYPE 2
set PWM_OUT 1234
param set-default ATT_BIAS_MAX 0
param set-default CBRK_IO_SAFETY 22027
@@ -15,10 +15,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
# The set does not include a battery, but most people will probably use 4S
param set-default BAT1_N_CELLS 4
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default BAT1_N_CELLS 4
param set-default GPS_1_CONFIG 0
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default BAT1_N_CELLS 6
param set-default MC_ROLLRATE_P 0.05
@@ -19,7 +19,6 @@
set MIXER none
set MIXER_AUX none
# Battery settings
param set-default BAT_CRIT_THR 0.20
param set-default BAT_LOW_THR 0.25
@@ -28,10 +28,8 @@ set PWM_OUT 1234
# Attitude & rate gains
param set-default MC_ROLLRATE_D 0.0013
param set-default MC_PITCHRATE_D 0.0016
param set-default MC_YAW_FF 0.5
param set-default MPC_MANTHR_MAX 0.9
@@ -22,10 +22,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
# use the Q attitude estimator, it works w/o mag or GPS.
param set-default SYS_MC_EST_GROUP 3
param set-default ATT_ACC_COMP 0
@@ -17,10 +17,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default BAT1_N_CELLS 1
param set-default MC_ROLL_P 8
@@ -31,5 +31,3 @@
# Set mixer
set MIXER tilt_quad
set MIXER_AUX tilt_quad
set PWM_OUT 1234
@@ -1,190 +0,0 @@
#!/bin/sh
#
# @name Teal One
#
# @type Quadrotor x
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
#
# @maintainer Matt McFadden <matt.mcfadden@tealdrones.com>
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v3 exclude
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board bitcraze_crazyflie exclude
#
echo "Executing 4250_teal script."
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
# First thing, reset all params to default... EXCEPT THIS LIST
param reset_all SYS_AUTOSTART SYS_AUTOCONFIG RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO* CAL_MAG* SENS_BOARD* EKF2_MAGBIAS*
# battery
param set-default BAT_CRIT_THR 0.15
param set-default BAT_EMERGEN_THR 0.075
param set-default BAT_LOW_THR 0.20
param set-default BAT1_CAPACITY 2750
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.06
param set-default BAT1_SOURCE 1
param set-default BAT1_V_CHARGED 4.15
param set-default BAT1_V_DIV 11.1625
param set-default BAT1_V_EMPTY 3.65
param set-default BAT1_V_OFFS_CURR -0.0045
# sensor calibration
param set-default CAL_MAG_SIDES 63
# circuit breakers
param set-default CBRK_IO_SAFETY 22027
param set-default CBRK_USB_CHK 197848
# commander
param set-default COM_DISARM_LAND 0.1
# Return mode at critically low level, Land mode at current position if reaching dangerously low levels.
param set-default COM_LOW_BAT_ACT 3
# ekf2
param set-default EKF2_MAG_TYPE 1
param set-default EKF2_GPS_CHECK 511
param set-default EKF2_GPS_POS_X -0.04
param set-default EKF2_IMU_POS_X -0.06
param set-default EKF2_PCOEF_XN 0.1
param set-default EKF2_PCOEF_XP -0.5
param set-default EKF2_RNG_A_VMAX 20
param set-default EKF2_RNG_NOISE 0.2
param set-default EKF2_MIN_RNG 0.07
# geofence
# Geofence violation action -- Warning.
param set-default GF_ACTION 1
# land detector
param set-default LNDMC_XY_VEL_MAX 1
# This is set high because we have lots of vibrations while in contact with ground.
param set-default LNDMC_ROT_MAX 50
# serial comms
param set-default SER_TEL1_BAUD 921600
param set-default SER_TEL2_BAUD 921600
# mavlink stream configuration
# TEL1 ttyS1 -- disabled. TX1 FTDI UART has issues.
param set-default MAV_0_CONFIG 0
param set-default MAV_0_RATE 800000
# TEL2 ttyS2 -- Primary MAVLINK stream to companion computer.
param set-default MAV_1_CONFIG 102
param set-default MAV_1_RATE 800000
# mc_att_control
param set-default MC_ACRO_P_MAX 360
param set-default MC_ACRO_R_MAX 360
param set-default MC_ACRO_Y_MAX 360
param set-default MC_ROLL_P 6
param set-default MC_ROLLRATE_P 0.055
param set-default MC_ROLLRATE_D 0.0012
param set-default MC_ROLLRATE_MAX 180
param set-default MC_PITCHRATE_P 0.06
param set-default MC_PITCHRATE_D 0.0012
param set-default MC_PITCHRATE_MAX 180
param set-default MC_YAW_P 1
param set-default MC_YAWRATE_P 0.08
param set-default MC_YAWRATE_I 0.08
param set-default MC_YAWRATE_MAX 180
# Set to reduce voltage transients as seen by battery management system.
param set-default MOT_SLEW_MAX 0.15
#### CONTROLLER ###
param set-default MPC_LAND_ALT1 8
param set-default MPC_LAND_ALT2 5
param set-default MPC_TKO_RAMP_T 0.75
param set-default MPC_TKO_SPEED 0.75
param set-default MPC_TILTMAX_LND 18
param set-default MPC_TILTMAX_AIR 45
param set-default MPC_MAN_TILT_MAX 45
param set-default MPC_MANTHR_MAX 0.85
param set-default MPC_MANTHR_MIN 0.15
# Full throttle can trip over current protection on BMS.
param set-default MPC_THR_MAX 0.85
param set-default MPC_THR_MIN 0.15
param set-default MPC_VEL_MANUAL 26.5
# RTL speed, it was too fast and scaring people.
param set-default MPC_XY_CRUISE 15
param set-default MPC_MAN_Y_MAX 200
param set-default MPC_JERK_MAX 5
param set-default MPC_ACC_UP_MAX 10
param set-default MPC_ACC_DOWN_MAX 10
param set-default MPC_ACC_HOR 10
param set-default MPC_ACC_HOR_MAX 15
param set-default MPC_XY_P 1.15
param set-default MPC_XY_VEL_P_ACC 2.8
param set-default MPC_XY_VEL_I_ACC 0.28
param set-default MPC_XY_VEL_D_ACC 0.28
param set-default MPC_XY_VEL_MAX 26.5
param set-default MPC_Z_P 0.85
param set-default MPC_Z_VEL_P_ACC 5
param set-default MPC_Z_VEL_I_ACC 1.7
param set-default MPC_Z_VEL_D_ACC 0.4
# Documentation says limit is 8.0, but does not seem to be enforced in code.
param set-default MPC_Z_VEL_MAX_UP 20
param set-default MPC_Z_VEL_MAX_DN 2.5
#### CONTROLLER ###
# navigator
param set-default NAV_ACC_RAD 2.5
# RC loss failsafe behavior -- hold mode.
param set-default NAV_RCL_ACT 1
# pwm control
param set-default PWM_MAIN_DISARM 900
param set-default PWM_MAIN_MAX 1850
param set-default PWM_MAIN_MIN 1075
# Oneshot125
param set-default PWM_MAIN_RATE 0
# rtl
param set-default RTL_DESCEND_ALT 5
param set-default RTL_LAND_DELAY 5
param set-default RTL_MIN_DIST 7.5
param set-default RTL_RETURN_ALT 25
# calibration
param set-default CAL_ACC0_PRIO 255
param set-default CAL_ACC1_PRIO 0
param set-default CAL_GYRO0_PRIO 255
param set-default CAL_GYRO1_PRIO 0
# Logger mode. Default(1) + estimator replay(2) + thermal calibration(4)
param set-default SDLOG_PROFILE 6
# Do not start frsky_telemetry on port ttyS6 by default, PGA460 lives there. 500 is in arbitrary unused number.
param set TEL_FRSKY_CONFIG 500
# We want to make sure these always start
param set SENS_EN_PGA460 1
param set SENS_EN_THERMAL 1
param set SENS_EN_BATT 1
@@ -13,10 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x
set PWM_OUT 1234
param set-default MC_PITCHRATE_P 0.087
param set-default MC_PITCHRATE_I 0.037
param set-default MC_PITCHRATE_D 0.0044
@@ -17,7 +17,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x_cw
set PWM_OUT 1234
param set-default BAT1_N_CELLS 1
param set-default BAT1_CAPACITY 240
@@ -69,4 +68,3 @@ set PWM_MAIN_MIN none
syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
@@ -17,7 +17,6 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_x_cw
set PWM_OUT 1234
param set-default SYS_MC_EST_GROUP 2
param set-default SYS_HAS_MAG 0
@@ -61,7 +60,6 @@ param set-default PWM_MAIN_RATE 3921
param set-default SENS_FLOW_MINRNG 0.05
set PWM_MAIN_DISARM none
set PWM_MAIN_MAX none
set PWM_MAIN_MIN none
@@ -18,7 +18,6 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT1_N_CELLS 4
param set-default EKF2_GBIAS_INIT 0.01
@@ -20,7 +20,6 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT1_N_CELLS 2
param set-default EKF2_GBIAS_INIT 0.01
@@ -26,5 +26,3 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER quad_+
set PWM_OUT 1234
@@ -22,7 +22,6 @@
. ${R}etc/init.d/rc.uuv_defaults
#Set data link loss failsafe mode (0: disabled)
# disable circuit breaker for airspeed sensor
@@ -43,4 +42,3 @@ param set-default BAT_V_OFFS_CURR 0.33
set PWM_OUT 12345678
# set MIXER IO_pass
set MIXER vectored6dof
@@ -26,6 +26,7 @@
#
. ${R}etc/init.d/rc.mc_defaults
set MIXER hexa_x
set PWM_OUT 12345678
@@ -13,7 +13,6 @@
. ${R}etc/init.d/rc.mc_defaults
. ${R}etc/init.d/rc.ctrlalloc
param set-default MPC_USE_HTE 0
param set-default VM_MASS 1.5
@@ -88,7 +88,6 @@ px4_add_romfs_files(
4080_zmr250
4090_nanomind
4100_tiltquadrotor
4250_teal
4500_clover4
4900_crazyflie
4901_crazyflie21
+2 -2
View File
@@ -8,8 +8,8 @@
#
# Start angular velocity controller
#
angular_velocity_controller start
mc_rate_control stop
# angular_velocity_controller start
# mc_rate_control stop
#
# Start Control Allocator
@@ -25,4 +25,8 @@ param set-default GPS_UBX_DYNMODEL 6
#
set MIXER_AUX pass
set MIXER quad_x
set PWM_OUT 1234
set PWM_AUX_OUT 1234
+7 -1
View File
@@ -108,7 +108,13 @@ fi
# Python3 dependencies
echo
echo "Installing PX4 Python3 dependencies"
python3 -m pip install --user -r ${DIR}/requirements.txt
if [ -n "$VIRTUAL_ENV" ]; then
# virtual envrionments don't allow --user option
python -m pip install -r ${DIR}/requirements.txt
else
# older versions of Ubuntu require --user option
python3 -m pip install --user -r ${DIR}/requirements.txt
fi
# NuttX toolchain (arm-none-eabi-gcc)
if [[ $INSTALL_NUTTX == "true" ]]; then
+1
View File
@@ -48,6 +48,7 @@
/* CAN termination software control */
#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
/* Boot config */
#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI)
+7
View File
@@ -60,6 +60,7 @@
/* CAN termination software control */
#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
/* ICM42688p FSYNC */
#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
@@ -78,6 +79,12 @@
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
#define FLASH_BASED_PARAMS
/* High-resolution timer */
+16
View File
@@ -55,6 +55,7 @@
#include <stm32.h>
#include "board_config.h"
#include "led.h"
#include <stm32_uart.h>
#include <arch/board/board.h>
@@ -92,6 +93,21 @@ __EXPORT void stm32_boardinitialize(void)
// Configure SPI all interfaces GPIO & enable power.
stm32_spiinitialize();
// Check if button is held. If so go into gps passthrough mode
if (stm32_gpioread(GPIO_BTN_SAFETY)) {
rgb_led(128, 128, 128, 10);
stm32_configgpio(GPIO_USART1_TX_GPIO);
stm32_configgpio(GPIO_USART1_RX_GPIO);
stm32_configgpio(GPIO_USART2_TX_GPIO);
stm32_configgpio(GPIO_USART2_RX_GPIO);
while (1) {
watchdog_pet();
stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
}
}
}
/****************************************************************************
+10
View File
@@ -60,6 +60,7 @@
/* CAN termination software control */
#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION
/* ICM42688p FSYNC */
#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
@@ -78,6 +79,15 @@
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
#define FLASH_BASED_PARAMS
/* High-resolution timer */
+16
View File
@@ -55,6 +55,7 @@
#include <stm32.h>
#include "board_config.h"
#include "led.h"
#include <stm32_uart.h>
#include <arch/board/board.h>
@@ -92,6 +93,21 @@ __EXPORT void stm32_boardinitialize(void)
// Configure SPI all interfaces GPIO & enable power.
stm32_spiinitialize();
// Check if button is held. If so go into gps passthrough mode
if (stm32_gpioread(GPIO_BTN_SAFETY)) {
rgb_led(128, 128, 128, 10);
stm32_configgpio(GPIO_USART1_TX_GPIO);
stm32_configgpio(GPIO_USART1_RX_GPIO);
stm32_configgpio(GPIO_USART2_TX_GPIO);
stm32_configgpio(GPIO_USART2_RX_GPIO);
while (1) {
watchdog_pet();
stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
}
}
}
/****************************************************************************
+2 -2
View File
@@ -254,11 +254,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
#if defined(SERIAL_HAVE_DMA) || defined(LPSERIAL_HAVE_DMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)kinetis_lpserial_dma_poll_all, NULL);
#endif
#endif /* SERIAL_HAVE_DMA || LPSERIAL_HAVE_DMA */
/* initial LED state */
drv_led_start();
+7
View File
@@ -1,2 +1,9 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
+2 -2
View File
@@ -254,11 +254,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
#if defined(SERIAL_HAVE_DMA) || defined(LPSERIAL_HAVE_DMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)kinetis_lpserial_dma_poll_all, NULL);
#endif
#endif /* SERIAL_HAVE_DMA || LPSERIAL_HAVE_DMA */
/* initial LED state */
drv_led_start();
@@ -21,6 +21,7 @@ CONFIG_ARCH_CHIP_S32K1XX=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BCH=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_LOOPSPERMSEC=3997
CONFIG_BUILTIN=y
@@ -33,6 +34,7 @@ CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_FS_CROMFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_MAX_TASKS=16
CONFIG_FS_ROMFS=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
@@ -52,7 +54,6 @@ CONFIG_LPUART0_TXDMA=y
CONFIG_LPUART1_RXBUFSIZE=128
CONFIG_LPUART1_SERIAL_CONSOLE=y
CONFIG_LPUART1_TXBUFSIZE=128
CONFIG_FS_PROCFS_MAX_TASKS=16
CONFIG_MOTOROLA_SREC=y
CONFIG_MTD=y
CONFIG_MTD_PARTITION=y
+10
View File
@@ -0,0 +1,10 @@
#!/bin/sh
#
# board specific MAVLink startup script.
#------------------------------------------------------------------------------
if ver hwtypecmp V5Xa0 V5X91 V5Xa1
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
fi
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
+1 -1
View File
@@ -46,7 +46,7 @@ endif()
add_custom_target(upload
COMMAND rsync -arh --progress
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/pilotpi*.config ${PX4_BINARY_DIR}/etc # source
\$\{AUTOPILOT_USER\}@\$\{AUTOPILOT_HOST\}:/home/\$\{AUTOPILOT_USER\}/px4 # destination
"${AUTOPILOT_USER}@${AUTOPILOT_HOST}:/home/${AUTOPILOT_USER}/px4" # destination
DEPENDS px4
COMMENT "uploading px4"
USES_TERMINAL
+2 -2
View File
@@ -150,7 +150,7 @@ static void mavlink_usb_check(void *arg)
if (nread >= MAVLINK_HEARTBEAT_MIN_LENGTH) {
// scan buffer for mavlink HEARTBEAT (v1 & v2)
for (int i = 0; i < nread - MAVLINK_HEARTBEAT_MIN_LENGTH; i++) {
if ((buffer[i] = 0xFE) && (buffer[i + 1] = 9) && (buffer[i + 5] == 0)) {
if ((buffer[i] == 0xFE) && (buffer[i + 1] == 9) && (buffer[i + 5] == 0)) {
// mavlink v1 HEARTBEAT
// buffer[0]: start byte (0xFE for mavlink v1)
// buffer[1]: length (9 for HEARTBEAT)
@@ -162,7 +162,7 @@ static void mavlink_usb_check(void *arg)
launch_mavlink = true;
break;
} else if ((buffer[i] = 0xFD) && (buffer[i + 1] = 9)
} else if ((buffer[i] == 0xFD) && (buffer[i + 1] == 9)
&& (buffer[i + 7] == 0) && (buffer[i + 8] == 0) && (buffer[i + 9] == 0)) {
// mavlink v2 HEARTBEAT
// buffer[0]: start byte (0xFD for mavlink v2)
+2
View File
@@ -120,6 +120,7 @@ set(models
believer
boat
cloudship
glider
if750a
iris
iris_ctrlalloc
@@ -147,6 +148,7 @@ set(models
techpod
tiltrotor
typhoon_h480
typhoon_h480_ctrlalloc
uuv_bluerov2_heavy
uuv_hippocampus
)
@@ -31,4 +31,4 @@
#
############################################################################
#add_subdirectory(afbrs50) # not suitable for general inclusion
add_subdirectory(afbrs50)
@@ -127,6 +127,13 @@ LightwareLaserSerial::init()
_simple_serial = true;
break;
case 8:
/* LW20/c (100M 20Hz) */
_px4_rangefinder.set_min_distance(0.2f);
_px4_rangefinder.set_max_distance(100.0f);
_interval = 50000;
break;
default:
PX4_ERR("invalid HW model %" PRIi32 ".", hw_model);
return -1;
@@ -297,6 +304,12 @@ void LightwareLaserSerial::Run()
if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
PX4_ERR("baud %d ATTR", termios_state);
}
// LW20: Enable serial mode by sending some characters
if (hw_model == 8) {
const char *data = "www\r\n";
(void)!::write(_fd, &data, strlen(data));
}
}
/* collection phase? */
@@ -41,5 +41,8 @@
* @value 3 SF10/b
* @value 4 SF10/c
* @value 5 SF11/c
* @value 6 SF30/b
* @value 7 SF30/c
* @value 8 LW20/c
*/
PARAM_DEFINE_INT32(SENS_EN_SF0X, 1);
@@ -274,15 +274,21 @@ void ICM20602::RunImpl()
if (samples > _fifo_gyro_samples) {
// grab desired number of samples, but reschedule next cycle sooner
int extra_samples = samples - _fifo_gyro_samples;
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
samples = _fifo_gyro_samples;
ScheduleOnInterval(_fifo_empty_interval_us,
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
if (_fifo_gyro_samples > extra_samples) {
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
} else {
// otherwise reschedule to run immediately
ScheduleOnInterval(_fifo_empty_interval_us);
}
} else if (samples < _fifo_gyro_samples) {
// reschedule next cycle to catch the desired number of samples
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
}
}
}
@@ -229,15 +229,21 @@ void ICM20649::RunImpl()
if (samples > _fifo_gyro_samples) {
// grab desired number of samples, but reschedule next cycle sooner
int extra_samples = samples - _fifo_gyro_samples;
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
samples = _fifo_gyro_samples;
ScheduleOnInterval(_fifo_empty_interval_us,
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
if (_fifo_gyro_samples > extra_samples) {
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
} else {
// otherwise reschedule to run immediately
ScheduleOnInterval(_fifo_empty_interval_us);
}
} else if (samples < _fifo_gyro_samples) {
// reschedule next cycle to catch the desired number of samples
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
}
if (samples == _fifo_gyro_samples) {
@@ -265,15 +265,21 @@ void ICM20948::RunImpl()
if (samples > _fifo_gyro_samples) {
// grab desired number of samples, but reschedule next cycle sooner
int extra_samples = samples - _fifo_gyro_samples;
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
samples = _fifo_gyro_samples;
ScheduleOnInterval(_fifo_empty_interval_us,
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
if (_fifo_gyro_samples > extra_samples) {
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
} else {
// otherwise reschedule to run immediately
ScheduleOnInterval(_fifo_empty_interval_us);
}
} else if (samples < _fifo_gyro_samples) {
// reschedule next cycle to catch the desired number of samples
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
}
if (samples == _fifo_gyro_samples) {
@@ -568,8 +568,8 @@ void DevCommon::cleanup()
size_t garbage_end = 0;
if (!mavlink_available && !rtps_available && (_read_buffer->buf_size > 0)) {
garbage_end = _read_buffer->buf_size - 1;
if (!mavlink_available && !rtps_available) {
garbage_end = math::max(_read_buffer->start_mavlink, _read_buffer->start_rtps);
} else {
garbage_end = math::min(_read_buffer->start_mavlink, _read_buffer->start_rtps);
+38 -2
View File
@@ -50,6 +50,8 @@ else()
endif()
set(SRCS)
set(DPNDS)
if(${PX4_PLATFORM} MATCHES "nuttx")
if(CONFIG_NET_CAN)
list(APPEND SRCS
@@ -64,6 +66,40 @@ if(${PX4_PLATFORM} MATCHES "nuttx")
endif()
endif()
if(CONFIG_UAVCAN_V1_NODE_MANAGER)
list(APPEND SRCS
NodeManager.hpp
NodeManager.cpp
)
endif()
if(CONFIG_UAVCAN_V1_NODE_CLIENT)
list(APPEND SRCS
NodeClient.hpp
NodeClient.cpp
)
list(APPEND DPNDS
drivers_bootloaders
)
endif()
# Temporary measure to get Kconfig option as defines into this application
# Ideally we want nicely decouple and define this in kconfig.cmake
# But then we need to overhaul the src modules naming convention
set(DRIVERS_UAVCAN_V1_OPTIONS)
get_cmake_property(_variableNames VARIABLES)
foreach (_variableName ${_variableNames})
string(REGEX MATCH "^CONFIG_UAVCAN_V1_" UAVCAN_V1_OPTION ${_variableName})
if(UAVCAN_V1_OPTION)
if(${${_variableName}} STREQUAL "y")
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=1")
else()
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=${${_variableName}}")
endif()
endif()
endforeach()
px4_add_module(
MODULE drivers__uavcan_v1
MAIN uavcan_v1
@@ -72,6 +108,7 @@ px4_add_module(
#-DCANARD_ASSERT
-DUINT32_C\(x\)=__UINT32_C\(x\)
-O0
${DRIVERS_UAVCAN_V1_OPTIONS}
INCLUDES
${LIBCANARD_DIR}/libcanard/
${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated
@@ -82,8 +119,6 @@ px4_add_module(
SubscriptionManager.hpp
ParamManager.hpp
ParamManager.cpp
NodeManager.hpp
NodeManager.cpp
Uavcan.cpp
Uavcan.hpp
Publishers/uORB/uorb_publisher.cpp
@@ -97,4 +132,5 @@ px4_add_module(
git_public_regulated_data_types
git_legacy_data_types
version
${DPNDS}
)
+84 -8
View File
@@ -20,15 +20,91 @@ if DRIVERS_UAVCAN_V1
endchoice
config UAVCAN_V1_GETINFO_RESPONDER
bool "GetInfo1.0 responder"
default n
config UAVCAN_V1_NODE_MANAGER
bool "Node manager"
default y
depends on UAVCAN_V1_FMU
help
Implement UAVCAN v1 PNP server functionality and manages discovered nodes
config UAVCAN_V1_EXECUTECOMMAND_RESPONDER
bool "ExecuteCommand1.0 responder"
default n
config UAVCAN_V1_NODE_CLIENT
bool "Node client"
default y
depends on UAVCAN_V1_CLIENT
help
Implement UAVCAN v1 PNP client functionality
config UAVCAN_V1_GNSS_PUBLISHER
bool "GNSS Publisher"
config UAVCAN_V1_APP_DESCRIPTOR
bool "UAVCAN v0 bootloader app descriptor"
default n
depends on UAVCAN_V1_CLIENT && DRIVERS_BOOTLOADERS
help
When the board uses the UAVCANv0 bootloader functionality you need a AppImageDescriptor defined
menu "Publisher support"
config UAVCAN_V1_GNSS_PUBLISHER
bool "GNSS Publisher"
default n
config UAVCAN_V1_ESC_CONTROLLER
bool "ESC Controller"
default n
config UAVCAN_V1_READINESS_PUBLISHER
bool "Readiness Publisher"
default n
config UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
bool "uORB actuator_outputs publisher"
default n
config UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
bool "uORB sensor_gps publisher"
default n
endmenu
menu "Subscriber support"
config UAVCAN_V1_ESC_SUBSCRIBER
bool "ESC Subscriber"
default n
config UAVCAN_V1_GNSS_SUBSCRIBER_0
bool "GNSS Subscriber 0 "
default n
config UAVCAN_V1_GNSS_SUBSCRIBER_1
bool "GNSS Subscriber 1"
default n
config UAVCAN_V1_BMS_SUBSCRIBER
bool "BMS Subscriber"
default n
config UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER
bool "uORB sensor_gps Subscriber"
default n
endmenu
menu "Advertised Services"
config UAVCAN_V1_GETINFO_RESPONDER
bool "GetInfo1.0 responder"
default y
help
Responds to uavcan.node.GetInfo.1.0 request sending over node information
See https://github.com/UAVCAN/public_regulated_data_types/blob/master/uavcan/node/430.GetInfo.1.0.uavcan for full response
config UAVCAN_V1_EXECUTECOMMAND_RESPONDER
bool "ExecuteCommand1.0 responder"
default n
help
To be implemented
endmenu
menu "Service invokers"
endmenu
endif #DRIVERS_UAVCAN_V1
+170
View File
@@ -0,0 +1,170 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file NodeClient.cpp
*
* Defines basic implementation of client UAVCAN PNP for requesting a Node ID
*
* @author Peter van der Perk <peter.vanderperk@nxp.com>
*/
#define PNP_UNIQUE_ID_SIZE 16 // 128 bit unique id
#include <crc64.h>
#include "NodeClient.hpp"
void NodeClient::callback(const CanardTransfer &receive)
{
if (receive.remote_node_id != CANARD_NODE_ID_UNSET && _canard_instance.node_id != CANARD_NODE_ID_UNSET) {
int32_t allocated = CANARD_NODE_ID_UNSET;
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
if (_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD) {
uavcan_pnp_NodeIDAllocationData_2_0 msg;
size_t msg_size_in_bytes = receive.payload_size;
uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&msg, (const uint8_t *)receive.payload,
&msg_size_in_bytes);
if (memcmp(msg.unique_id, px4_guid, sizeof(msg.unique_id)) == 0) {
allocated = msg.node_id.value;
}
} else {
uavcan_pnp_NodeIDAllocationData_1_0 msg;
size_t msg_size_in_bytes = receive.payload_size;
uavcan_pnp_NodeIDAllocationData_1_0_deserialize_(&msg, (const uint8_t *)receive.payload,
&msg_size_in_bytes);
if (msg.allocated_node_id.count > 0) {
if (msg.unique_id_hash == (crc64(px4_guid, PNP_UNIQUE_ID_SIZE) & 0xFFFFFFFFFFFF)) {
allocated = msg.allocated_node_id.elements[0].value;
}
}
}
if (allocated == CANARD_NODE_ID_UNSET) {
return; // UID mismatch.
}
if (allocated <= 0 || allocated >= (int32_t)CANARD_NODE_ID_MAX)
// Allocated node-ID ignored because it exceeds max_node_id
{
return;
}
_canard_instance.node_id = allocated;
}
}
void NodeClient::update()
{
if (hrt_elapsed_time(&_nodealloc_request_last) >= hrt_abstime(2 *
1000000ULL)) { // Compiler hates me here, some 1_s doesn't work
int32_t result;
// Allocation already done, nothing to do
if (_canard_instance.node_id != CANARD_NODE_ID_UNSET) {
return;
}
if (_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD) {
// NodeIDAllocationData message
uavcan_pnp_NodeIDAllocationData_2_0 node_id_alloc_msg;
uint8_t node_id_alloc_payload_buffer[PNP2_PAYLOAD_SIZE];
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
memcpy(node_id_alloc_msg.unique_id, px4_guid, sizeof(node_id_alloc_msg.unique_id));
//node_id_alloc_msg.node_id.value = preffered_node_id; //FIXME preffered ID PX4 Param
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, // Zero if transmission deadline is not limited.
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = PNP2_PORT_ID, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _node_id_alloc_transfer_id,
.payload_size = PNP2_PAYLOAD_SIZE,
.payload = &node_id_alloc_payload_buffer,
};
result = uavcan_pnp_NodeIDAllocationData_2_0_serialize_(&node_id_alloc_msg, (uint8_t *)&node_id_alloc_payload_buffer,
&transfer.payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_node_id_alloc_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
canardTxPush(&_canard_instance, &transfer);
}
} else {
// NodeIDAllocationData message
uavcan_pnp_NodeIDAllocationData_1_0 node_id_alloc_msg;
uavcan_pnp_NodeIDAllocationData_1_0_initialize_(&node_id_alloc_msg);
uint8_t node_id_alloc_payload_buffer[PNP1_PAYLOAD_SIZE];
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
node_id_alloc_msg.unique_id_hash = (crc64(px4_guid, PNP_UNIQUE_ID_SIZE) & 0xFFFFFFFFFFFF);
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, // Zero if transmission deadline is not limited.
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = PNP1_PORT_ID, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _node_id_alloc_transfer_id,
.payload_size = PNP1_PAYLOAD_SIZE,
.payload = &node_id_alloc_payload_buffer,
};
result = uavcan_pnp_NodeIDAllocationData_1_0_serialize_(&node_id_alloc_msg, (uint8_t *)&node_id_alloc_payload_buffer,
&transfer.payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_node_id_alloc_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
canardTxPush(&_canard_instance, &transfer);
}
}
_nodealloc_request_last = hrt_absolute_time();
}
}
+41 -2
View File
@@ -42,6 +42,35 @@
#pragma once
#include <px4_platform_common/px4_config.h>
#ifndef CONFIG_UAVCAN_V1_GNSS_PUBLISHER
#define CONFIG_UAVCAN_V1_GNSS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_ESC_CONTROLLER
#define CONFIG_UAVCAN_V1_ESC_CONTROLLER 0
#endif
#ifndef CONFIG_UAVCAN_V1_READINESS_PUBLISHER
#define CONFIG_UAVCAN_V1_READINESS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
#define CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
#define CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER 0
#endif
/* Preprocessor calculation of publisher count */
#define UAVCAN_PUB_COUNT CONFIG_UAVCAN_V1_GNSS_PUBLISHER + \
CONFIG_UAVCAN_V1_ESC_CONTROLLER + \
CONFIG_UAVCAN_V1_READINESS_PUBLISHER + \
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER + \
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
#include <px4_platform_common/defines.h>
#include <drivers/drv_hrt.h>
@@ -79,7 +108,9 @@ private:
UavcanParamManager &_param_manager;
List<UavcanPublisher *> _dynpublishers;
const UavcanDynPubBinder _uavcan_pubs[5] {
const UavcanDynPubBinder _uavcan_pubs[UAVCAN_PUB_COUNT] {
#if CONFIG_UAVCAN_V1_GNSS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
{
@@ -88,6 +119,8 @@ private:
"gps",
0
},
#endif
#if CONFIG_UAVCAN_V1_ESC_CONTROLLER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
{
@@ -96,6 +129,8 @@ private:
"esc",
0
},
#endif
#if CONFIG_UAVCAN_V1_READINESS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
{
@@ -104,6 +139,8 @@ private:
"readiness",
0
},
#endif
#if CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
{
@@ -112,7 +149,8 @@ private:
"uorb.actuator_outputs",
0
},
#endif
#if CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
{
@@ -121,5 +159,6 @@ private:
"uorb.sensor_gps",
0
},
#endif
};
};

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