Compare commits

..

1 Commits

Author SHA1 Message Date
Daniel Agar f706e3541d drivers/gps: set system clock more aggressively 2021-09-13 14:01:25 -04:00
184 changed files with 4649 additions and 4560 deletions
+18 -21
View File
@@ -825,7 +825,7 @@ pipeline {
}
options {
buildDiscarder(logRotator(numToKeepStr: '30', artifactDaysToKeepStr: '60'))
timeout(time: 180, unit: 'MINUTES')
timeout(time: 120, unit: 'MINUTES')
skipDefaultCheckout()
}
}
@@ -899,9 +899,6 @@ void resetParameters() {
void runTests() {
resetParameters()
sh './Tools/HIL/nsh_param_set.py --device `find /dev/serial -name *usb-*` --name "IMU_GYRO_CAL_EN" --value "0" || true' // disable during testing
sh './Tools/HIL/nsh_param_set.py --device `find /dev/serial -name *usb-*` --name "IMU_GYRO_FFT_EN" --value "0" || true' // disable during testing
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param save"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "reboot" || true' // reboot to apply
@@ -1050,25 +1047,25 @@ void resetBoard() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "reboot" || true' // reboot to apply
// check SD card
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage"'
// format
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman stop" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "umount /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman stop"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "umount /fs/microsd"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mkfatfs -F 32 /dev/mmcsd0" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount -t vfat /dev/mmcsd0 /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount -t vfat /dev/mmcsd0 /fs/microsd"'
// check SD card
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage"'
}
-8
View File
@@ -66,11 +66,3 @@
[submodule "Tools/simulation-ignition"]
path = Tools/simulation-ignition
url = https://github.com/Auterion/px4-simulation-ignition.git
[submodule "src/lib/crypto/libtomcrypt"]
path = src/lib/crypto/libtomcrypt
url = https://github.com/PX4/libtomcrypt.git
branch = px4
[submodule "src/lib/crypto/libtommath"]
path = src/lib/crypto/libtommath
url = https://github.com/PX4/libtommath.git
branch = px4
+1
View File
@@ -31,6 +31,7 @@
"esc"
],
"debug.toolBarLocation": "docked",
"editor.acceptSuggestionOnEnter": "off",
"editor.defaultFormatter": "chiehyu.vscode-astyle",
"editor.dragAndDrop": false,
"editor.insertSpaces": false,
+5 -13
View File
@@ -110,22 +110,14 @@ include(px4_parse_function_args)
#=============================================================================
# git
#
find_package(Git QUIET)
include(px4_git)
# sync submodules
execute_process(
COMMAND ${GIT_EXECUTABLE} submodule sync --recursive --quiet
OUTPUT_VARIABLE GIT_SUBMODULE_SYNC
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
execute_process(
COMMAND ${GIT_EXECUTABLE} describe --exclude ext/* --always --tags
OUTPUT_VARIABLE PX4_GIT_TAG
OUTPUT_STRIP_TRAILING_WHITESPACE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
COMMAND git describe --exclude ext/* --always --tags
OUTPUT_VARIABLE PX4_GIT_TAG
OUTPUT_STRIP_TRAILING_WHITESPACE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
message(STATUS "PX4 version: ${PX4_GIT_TAG}")
define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES
+2
View File
@@ -120,6 +120,8 @@ then
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_RESTART_TYPE 2
fi
param set-default BAT1_N_CELLS 4
@@ -42,6 +42,7 @@ px4_add_romfs_files(
rc.fw_apps
rc.fw_defaults
rc.interface
rc.io
rc.logging
rc.mc_apps
rc.mc_defaults
@@ -56,6 +56,7 @@ param set-default RTL_DESCEND_ALT 10
param set-default RTL_RETURN_ALT 30
param set-default SDLOG_DIRS_MAX 7
param set-default SYS_RESTART_TYPE 2
param set-default VT_F_TRANS_THR 0.75
param set-default VT_MOT_ID 1234
@@ -48,6 +48,7 @@ param set-default CBRK_IO_SAFETY 22027
param set-default CBRK_SUPPLY_CHK 894281
# RC configuration
param set-default RC_MAP_MODE_SW 5
param set-default RC_MAP_PITCH 2
param set-default RC_MAP_ROLL 1
param set-default RC_MAP_THROTTLE 3
+17 -13
View File
@@ -17,10 +17,6 @@ set OUTPUT_DEV none
set OUTPUT_AUX_DEV /dev/pwm_output1
set OUTPUT_EXTRA_DEV /dev/pwm_output0
# set these before starting the modules
param set PWM_AUX_OUT ${PWM_AUX_OUT}
param set PWM_MAIN_OUT ${PWM_OUT}
#
# If mount (gimbal) control is enabled and output mode is AUX, set the aux
# mixer to mount (override the airframe-specific MIXER_AUX setting).
@@ -82,16 +78,9 @@ then
fi
fi
#
# Start IO for PWM output or RC input if needed.
#
if [ $IO_PRESENT = yes ]
if [ $OUTPUT_MODE = io ]
then
if ! px4io start
then
echo "PX4IO start failed"
tune_control play -t 18 # PROG_PX4IO_ERR
fi
. ${R}etc/init.d/rc.io
fi
if [ $OUTPUT_MODE = $OUTPUT_CMD -o $OUTPUT_MODE = io ]
@@ -102,6 +91,17 @@ then
tune_control play error
fi
fi
#
# Start IO for RC input if needed.
#
if [ $IO_PRESENT = yes ]
then
if [ $OUTPUT_MODE != io ]
then
. ${R}etc/init.d/rc.io
fi
fi
fi
if [ $MIXER != none -a $MIXER != skip ]
@@ -212,6 +212,8 @@ then
fi
fi
param set PWM_AUX_OUT ${PWM_AUX_OUT}
if [ $OUTPUT_MODE = pwm_out -o $OUTPUT_MODE = io ]
then
if [ $PWM_OUT != none ]
@@ -224,6 +226,8 @@ then
fi
fi
param set PWM_MAIN_OUT ${PWM_OUT}
if [ $EXTRA_MIXER_MODE != none ]
then
+23
View File
@@ -0,0 +1,23 @@
#!/bin/sh
#
# PX4IO interface init script.
#
# If $OUTPUT_MODE indicated Hardware-int-the-loop simulation, px4io should not publish actuator_outputs,
# instead, pwm_out_sim will publish that uORB
if [ $OUTPUT_MODE = hil ]
then
set HIL_ARG $OUTPUT_MODE
fi
if [ $IO_PRESENT = yes ]
then
if px4io start $HIL_ARG
then
# Allow PX4IO to recover from midair restarts.
px4io recovery
else
echo "PX4IO start failed"
tune_control play -t 18 # PROG_PX4IO_ERR
fi
fi
@@ -13,8 +13,6 @@ param set-default MIS_YAW_TMT 10
param set-default EKF2_ARSP_THR 10
param set-default EKF2_FUSE_BETA 1
param set-default HTE_VXY_THR 2.0
param set-default MIS_DIST_WPS 5000
param set-default MPC_ACC_HOR_MAX 2
+8 -9
View File
@@ -70,6 +70,14 @@ then
set io_file /etc/extras/px4_io-v2_default.bin
fi
if px4io start
then
echo "PX4IO OK"
else
set unit_test_failure 1
set unit_test_failure_list "${unit_test_failure_list} px4io_start"
fi
if px4io checkcrc $io_file
then
echo "PX4IO CRC OK"
@@ -96,15 +104,6 @@ else
fi
fi
if px4io start
then
echo "PX4IO OK"
else
set unit_test_failure 1
set unit_test_failure_list "${unit_test_failure_list} px4io_start"
fi
#
# The presence of this file suggests we're running a mount stress test
#
+1 -1
View File
@@ -70,7 +70,7 @@ def do_nsh_cmd(port, baudrate, cmd):
success_cmd = "cmd succeeded!"
# wait for command echo
serial_cmd = '{0}; echo "{1}"; echo "{2}";\r\n'.format(cmd, success_cmd, success_cmd)
serial_cmd = '{0}; echo "{1}"\r\n'.format(cmd, success_cmd)
ser.write(serial_cmd.encode("ascii"))
ser.flush()
while True:
+3
View File
@@ -142,6 +142,9 @@ class TestHardwareMethods(unittest.TestCase):
def test_bson(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "bson"))
def test_conv(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "conv"))
def test_dataman(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "dataman"))
@@ -24,7 +24,4 @@ exec find boards msg src platforms test \
-path src/modules/micrortps_bridge/micro-CDR -prune -o \
-path src/modules/micrortps_bridge/microRTPS_client -prune -o \
-path test/mavsdk_tests/catch2 -prune -o \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/crypto/libtomcrypt -prune -o \
-path src/lib/crypto/libtommath -prune -o \
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN
+85
View File
@@ -0,0 +1,85 @@
#!/usr/bin/env bash
function check_git_submodule {
# The .git exists in a submodule if init and update have been done.
if [[ -f $1"/.git" || -d $1"/.git" ]]; then
# always update within CI environment or configuring withing VSCode CMake where you can't interact
if [ "$CI" == "true" ] || [ -n "${VSCODE_PID+set}" ]; then
git submodule --quiet sync --recursive -- $1
git submodule --quiet update --init --recursive --jobs=8 -- $1 || true
git submodule --quiet update --init --recursive --jobs=8 -- $1
exit 0
fi
SUBMODULE_STATUS=$(git submodule summary "$1")
STATUSRETVAL=$(echo $SUBMODULE_STATUS | grep -A20 -i "$1")
if ! [[ -z "$STATUSRETVAL" ]]; then
echo -e "\033[31mChecked $1 submodule, ACTION REQUIRED:\033[0m"
echo ""
echo -e "Different commits:"
echo -e "$SUBMODULE_STATUS"
echo ""
echo ""
echo -e " *******************************************************************************"
echo -e " * \033[31mIF YOU DID NOT CHANGE THIS FILE (OR YOU DON'T KNOW WHAT A SUBMODULE IS):\033[0m *"
echo -e " * \033[31mHit 'u' and <ENTER> to update ALL submodules and resolve this.\033[0m *"
echo -e " * (performs \033[94mgit submodule sync --recursive\033[0m *"
echo -e " * and \033[94mgit submodule update --init --recursive\033[0m ) *"
echo -e " *******************************************************************************"
echo ""
echo ""
echo -e " Only for EXPERTS:"
echo -e " $1 submodule is not in the recommended version."
echo -e " Hit 'y' and <ENTER> to continue the build with this version. Hit <ENTER> to resolve manually."
echo -e " Use \033[94mgit add $1 && git commit -m 'Updated $1'\033[0m to choose this version (careful!)"
echo ""
read user_cmd
if [ "$user_cmd" == "y" ]; then
echo "Continuing build with manually overridden submodule.."
elif [ "$user_cmd" == "u" ]; then
git submodule sync --recursive -- $1
git submodule update --init --recursive -- $1 || true
git submodule update --init --recursive --force -- $1
echo "Submodule fixed, continuing build.."
else
echo "Build aborted."
exit 1
fi
fi
else
git submodule --quiet sync --recursive --quiet -- $1
git submodule --quiet update --init --recursive -- $1 || true
git submodule --quiet update --init --recursive -- $1
fi
}
# If called with a path then respect $GIT_SUBMODULES_ARE_EVIL but do normal processing
if [ "$#" != "0" ]; then
# called with a path then process only that path but respect $GIT_SUBMODULES_ARE_EVIL
[ -n "$GIT_SUBMODULES_ARE_EVIL" ] && {
# GIT_SUBMODULES_ARE_EVIL is set, meaning user doesn't want submodules updated
exit 0
}
check_git_submodule $1
else
[ -n "$GIT_SUBMODULES_ARE_EVIL" ] && {
# GIT_SUBMODULES_ARE_EVIL is set, meaning user doesn't want submodules updated
echo "GIT_SUBMODULES_ARE_EVIL is defined - Skipping All submodule checking!"
exit 0
}
submodules=$(git submodule status | awk '{ print $2 }')
for i in $submodules;
do
check_git_submodule $i
done
fi
exit 0
-62
View File
@@ -1,62 +0,0 @@
#!/usr/bin/env python3
from Crypto.PublicKey import RSA
from Crypto.Cipher import PKCS1_OAEP
from Crypto.Cipher import ChaCha20
from Crypto.Hash import SHA256
import binascii
import argparse
#from pathlib import Path
import sys
if __name__ == "__main__":
parser = argparse.ArgumentParser(description="""CLI tool to decrypt an ulog file\n""")
parser.add_argument("ulog_file", help=".ulog file", nargs='?', default=None)
parser.add_argument("ulog_key", help=".ulogk, encrypted key", nargs='?', default=None)
parser.add_argument("rsa_key", help=".pem format key for decrypting the ulog key", nargs='?', default=None)
args = parser.parse_args()
# Only generate a key pair, don't sign
if not args.ulog_file or not args.ulog_key or not args.rsa_key:
print('Need all arguments, the encrypted ulog file, the key and the key decryption key')
sys.exit(1);
# Read the private RSA key to decrypt the cahcha key
with open(args.rsa_key, 'rb') as f:
r = RSA.importKey(f.read(), passphrase='')
# Read the encrypted xchacha key and the nonce
with open(args.ulog_key, 'rb') as f:
ulog_key_header = f.read(22)
# Parse the header
try:
# magic
if not ulog_key_header.startswith(bytearray("ULogKey".encode())):
raise Exception()
# version
if ulog_key_header[7] != 1:
raise Exception()
# expected key exchange algorithm (RSA_OAEP)
if ulog_key_header[16] != 4:
raise Exception()
key_size = ulog_key_header[19] << 8 | ulog_key_header[18];
nonce_size = ulog_key_header[21] << 8 | ulog_key_header[20];
ulog_key_cipher = f.read(key_size)
nonce = f.read(nonce_size)
except:
print("Keyfile format error")
sys.exit(1);
# Decrypt the xchacha key
cipher_rsa = PKCS1_OAEP.new(r,SHA256)
ulog_key = cipher_rsa.decrypt(ulog_key_cipher)
#print(binascii.hexlify(ulog_key))
# Read and decrypt the .ulgc
cipher = ChaCha20.new(key=ulog_key, nonce=nonce)
with open(args.ulog_file, 'rb') as f:
with open(args.ulog_file.rstrip(args.ulog_file[-1]), 'wb') as out:
out.write(cipher.decrypt(f.read()))
+1 -2
View File
@@ -126,8 +126,7 @@ else
m=0
while [ $m -lt ${target_number} ]; do
export PX4_SIM_MODEL=${target_vehicle}${LABEL}
spawn_model ${target_vehicle}${LABEL} $n $target_x $target_y
spawn_model ${target_vehicle} $n $target_x $target_y
m=$(($m + 1))
n=$(($n + 1))
done
-6
View File
@@ -138,12 +138,6 @@ serial_ports = {
"default_baudrate": 1, # set default to an unusable value to detect that this serial port has not been configured
},
# Pixhawk Payload Bus
"PPB": {
"label": "Pixhawk Payload Bus",
"index": 401,
"default_baudrate": 57600,
},
}
+1 -3
View File
@@ -1,7 +1,5 @@
#! /usr/bin/env bash
set -e
## Bash script to setup PX4 development environment on Ubuntu LTS (20.04, 18.04, 16.04).
## Can also be used in docker.
##
@@ -195,7 +193,7 @@ if [[ $INSTALL_SIM == "true" ]]; then
java_version=11
gazebo_version=9
elif [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then
java_version=13
java_version=14
gazebo_version=11
else
java_version=14
-27
View File
@@ -1,27 +0,0 @@
-----BEGIN RSA PRIVATE KEY-----
MIIEowIBAAKCAQEAz6O47E+sN+Yb+h6zkukagzYtJ6ZKq344b5N6H2CDg6z9LmG/
GRAfOeNstsz1hXyyOCcUQ9f+vKHofTN0k+fWKy95h1mwY5Vc509gRsmpD96pNp4+
NLp3GFDjawOTqsfyLQ7zKwU0YKT3qeI3o20n2KNxnGuyXt0SK3Ph2530wwzWBR2s
pNxpKvV8MCR7K4AbeuxodxKXKrLl0v9BHfUGpLZHpfoFfvChuK3eXK4si06tr6xt
RmLh6f6hxcn0SNKAK+WpPsH8mN4DqayGt7UZ5XVqY4M/J3pe+PFtstI2ocDSX5Oc
kOg+yonXytDH6I9Lt2CSXjZDcCM2+7WlBprAywIDAQABAoIBAGZE1nUV/NX/cXIt
IvdN9q//xBfOUOLMpVFXSwQfTkdRsdXhcPUQOsERYd9bbeZUd5cusE2GGkKgYFki
Od4LhzH4DRx8MWOrEnofX2UeODXHzoJHSI5B9Ry14n034shv+Lj2rxBWXOjo987l
y8+jmMecIP4REWal7igWyHyZ/Q7/5UCCCH5HaA4jgMhMdrD3zdxrlPhrW/egjfKF
Q+444qG5HzUqh7tOBxvf9Yu9FujHC9NxKDNXZZ3WBpwVQIVPCxexb4b8FBZ4syCH
iPbSgyw91CVfMvpWCYqDe7ubw4QDLHzDIiyKFtvHmIOgPo74y8fi1YYZ+3dy5mpa
UNdC11kCgYEA3whbNd71AVcSykRZ23AxDcjtUoiFXlpzSFes0QBGrmi2WTc04r8d
5Zr1E8oohc/zPJnUnCh93BAAu+HJsg4wKCqOWu5qR3NWcFp4/4voG9hsg1hgWD8Z
6fMMjoZRezSxadyeeaDStnfSkYyE2J8DPpkK5mjFG9IbrylGfApzDf0CgYEA7lTi
j2NQ+HNMlp/oOtsRZHkQtHYutv5SltG4E4DlwDHyA2ZLR2xB+D2ce5VdPQvfHu8F
ioMquDLeJbOPeikwko+RmpbmCsODjLueZHBmGwAfkuE0A5TZUwTi+W6iYbrXLK6E
TgNMaS4AGeBbioo6cdnMnYp9jdm63zvefet6oGcCgYAwr4BJmCvfaQR/BsCeuDTd
D3lOxOJoIFJ9/jWJQggr1kvH2dc/j/yUvGi3My/5VdWA6wuQMv6WZR/j43vF1HcK
rY95pgWpJzI9QGKdVgsK2QmG+mm9mbisaxPYoNV0kaIQu8oUPtkAX9OlVglByCRL
K9lHRqOQWSMV72qldRp8eQKBgHVCJkXN42SZtbDV8/ghGCmKtwFStCEsd43kmOBf
pqos6JlrltYJGVv9VCQplLoYQSqDBwLjDf2aaVm7QngkE9XH9SdN3tik4PA4zvEz
q8jVArPNQT4R2erSmKmIGTRkLMG7CzUmwk1taHdSvzcmUyL4uYc5QBSubxat6gWh
+a85AoGBAKgfnjjVoAWWvqEDLpfGPmE8lW+RaS7i5ff6QsSBx7uTEnHq6RNHuVnN
et4pR87yIENeG8jMBiDCj8AGDtUNt9Ps9vWCPrf9HSOYoBUk+gZagU/9N+RBpuCM
egoxtxIHM7HI+XIer+ZnZpVpgr+EoCaL7avx6k/susLQb7tqSBt1
-----END RSA PRIVATE KEY-----
-38
View File
@@ -1,38 +0,0 @@
0x30, 0x82, 0x1, 0x22, 0x30, 0xd, 0x6, 0x9,
0x2a, 0x86, 0x48, 0x86, 0xf7, 0xd, 0x1, 0x1,
0x1, 0x5, 0x0, 0x3, 0x82, 0x1, 0xf, 0x0,
0x30, 0x82, 0x1, 0xa, 0x2, 0x82, 0x1, 0x1,
0x0, 0xcf, 0xa3, 0xb8, 0xec, 0x4f, 0xac, 0x37,
0xe6, 0x1b, 0xfa, 0x1e, 0xb3, 0x92, 0xe9, 0x1a,
0x83, 0x36, 0x2d, 0x27, 0xa6, 0x4a, 0xab, 0x7e,
0x38, 0x6f, 0x93, 0x7a, 0x1f, 0x60, 0x83, 0x83,
0xac, 0xfd, 0x2e, 0x61, 0xbf, 0x19, 0x10, 0x1f,
0x39, 0xe3, 0x6c, 0xb6, 0xcc, 0xf5, 0x85, 0x7c,
0xb2, 0x38, 0x27, 0x14, 0x43, 0xd7, 0xfe, 0xbc,
0xa1, 0xe8, 0x7d, 0x33, 0x74, 0x93, 0xe7, 0xd6,
0x2b, 0x2f, 0x79, 0x87, 0x59, 0xb0, 0x63, 0x95,
0x5c, 0xe7, 0x4f, 0x60, 0x46, 0xc9, 0xa9, 0xf,
0xde, 0xa9, 0x36, 0x9e, 0x3e, 0x34, 0xba, 0x77,
0x18, 0x50, 0xe3, 0x6b, 0x3, 0x93, 0xaa, 0xc7,
0xf2, 0x2d, 0xe, 0xf3, 0x2b, 0x5, 0x34, 0x60,
0xa4, 0xf7, 0xa9, 0xe2, 0x37, 0xa3, 0x6d, 0x27,
0xd8, 0xa3, 0x71, 0x9c, 0x6b, 0xb2, 0x5e, 0xdd,
0x12, 0x2b, 0x73, 0xe1, 0xdb, 0x9d, 0xf4, 0xc3,
0xc, 0xd6, 0x5, 0x1d, 0xac, 0xa4, 0xdc, 0x69,
0x2a, 0xf5, 0x7c, 0x30, 0x24, 0x7b, 0x2b, 0x80,
0x1b, 0x7a, 0xec, 0x68, 0x77, 0x12, 0x97, 0x2a,
0xb2, 0xe5, 0xd2, 0xff, 0x41, 0x1d, 0xf5, 0x6,
0xa4, 0xb6, 0x47, 0xa5, 0xfa, 0x5, 0x7e, 0xf0,
0xa1, 0xb8, 0xad, 0xde, 0x5c, 0xae, 0x2c, 0x8b,
0x4e, 0xad, 0xaf, 0xac, 0x6d, 0x46, 0x62, 0xe1,
0xe9, 0xfe, 0xa1, 0xc5, 0xc9, 0xf4, 0x48, 0xd2,
0x80, 0x2b, 0xe5, 0xa9, 0x3e, 0xc1, 0xfc, 0x98,
0xde, 0x3, 0xa9, 0xac, 0x86, 0xb7, 0xb5, 0x19,
0xe5, 0x75, 0x6a, 0x63, 0x83, 0x3f, 0x27, 0x7a,
0x5e, 0xf8, 0xf1, 0x6d, 0xb2, 0xd2, 0x36, 0xa1,
0xc0, 0xd2, 0x5f, 0x93, 0x9c, 0x90, 0xe8, 0x3e,
0xca, 0x89, 0xd7, 0xca, 0xd0, 0xc7, 0xe8, 0x8f,
0x4b, 0xb7, 0x60, 0x92, 0x5e, 0x36, 0x43, 0x70,
0x23, 0x36, 0xfb, 0xb5, 0xa5, 0x6, 0x9a, 0xc0,
0xcb, 0x2, 0x3, 0x1, 0x0, 0x1,
+1 -3
View File
@@ -1,7 +1,5 @@
include (${CMAKE_CURRENT_LIST_DIR}/uavcan_board_identity)
add_definitions(-DCONSTRAINED_FLASH_NO_HELP="https://docs.px4.io/master/en/modules/modules_main.html")
px4_add_board(
PLATFORM nuttx
TOOLCHAIN arm-none-eabi
@@ -27,7 +25,7 @@ px4_add_board(
#i2cdetect
#led_control
param
#perf
perf
reboot
top
topic_listener
@@ -53,6 +53,7 @@
#include <fcntl.h>
#include <mqueue.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_board_led.h>
#include <systemlib/err.h>
@@ -95,7 +96,7 @@ Syslink::Syslink() :
_fd(0),
_queue(2, sizeof(syslink_message_t)),
_writebuffer(16, sizeof(crtp_message_t)),
_rssi(input_rc_s::RSSI_MAX),
_rssi(RC_INPUT_RSSI_MAX),
_bstate(BAT_DISCHARGING)
{
px4_sem_init(&memory_sem, 0, 0);
@@ -103,8 +103,6 @@
#define GPIO_SENSOR_3V3_EN /* PC15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_SENSOR_3V3_EN, (on_true))
#define GPIO_MCU_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6)
#define GPIO_MCU_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7)
-2
View File
@@ -135,8 +135,6 @@ stm32_boardinitialize(void)
__EXPORT int board_app_initialize(uintptr_t arg)
{
VDD_3V3_SENSORS_EN(true);
px4_platform_init();
if (OK == board_determine_hw_info()) {
@@ -265,7 +265,7 @@
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF9 */
/* I2C */
+1 -2
View File
@@ -14,8 +14,7 @@ px4_add_board(
DRIVERS
#adc/ads1115
adc/board_adc
#barometer # all available barometer drivers
barometer/ms5611
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
@@ -159,12 +159,8 @@
#define PIN_CAN0_TX PIN_CAN0_TX_4 /* PTE5 */
#define PIN_CAN0_RX PIN_CAN0_RX_4 /* PTE4 */
#define PIN_CAN0_STB (GPIO_OUTPUT | PIN_PORTE | PIN11 )
#define PIN_CAN0_ERRN (GPIO_INPUT | PIN_PORTA | PIN11 )
#define PIN_CAN0_EN (GPIO_HIGHDRIVE | PIN_PORTA | PIN10 )
#define PIN_CAN1_TX PIN_CAN1_TX_1 /* PTA13 */
#define PIN_CAN1_RX PIN_CAN1_RX_1 /* PTA12 */
#define PIN_CAN1_STB (GPIO_OUTPUT | PIN_PORTE | PIN10 )
#define PIN_CAN1_ERRN (GPIO_PULLDOWN | PIN_PORTE | PIN6 )
#define PIN_CAN1_EN (GPIO_OUTPUT | PIN_PORTE | PIN2 )
#endif /* __BOARDS_ARM_RDDRONE_UAVCAN146_INCLUDE_BOARD_H */
+2 -27
View File
@@ -75,32 +75,8 @@ __EXPORT void s32k1xx_board_initialize(void)
s32k1xx_pinconfig(BOARD_REVISION_DETECT_PIN);
if (s32k1xx_gpioread(BOARD_REVISION_DETECT_PIN)) {
/* Config Pins to do CAN tranceiver HW selftest */
s32k1xx_pinconfig(PIN_CAN0_ERRN);
s32k1xx_pinconfig(PIN_CAN0_STB);
s32k1xx_pinconfig(PIN_CAN0_EN);
/* EN high & STB high -> normal mode */
s32k1xx_gpiowrite(PIN_CAN0_STB, 1);
s32k1xx_gpiowrite(PIN_CAN0_EN, 1);
up_udelay(3000); // Wait for startup to normal mode
/* EN low & STB high -> listen only mode */
s32k1xx_gpiowrite(PIN_CAN0_STB, 1);
s32k1xx_gpiowrite(PIN_CAN0_EN, 0);
up_udelay(100); // t moch ERRN_N
/* Check for HW err and wait untill ERR has been cleared */
while (!s32k1xx_gpioread(PIN_CAN0_ERRN)) {
board_indicate(hardware_failure);
s32k1xx_gpiowrite(PIN_CAN0_EN, 1);
up_udelay(50);
s32k1xx_gpiowrite(PIN_CAN0_EN, 0);
up_udelay(50);
}
/* Enter normal-mode */
s32k1xx_gpiowrite(PIN_CAN0_EN, 1);
/* STB high -> active CAN phy */
s32k1xx_pinconfig(PIN_CAN0_STB | GPIO_OUTPUT_ONE);
} else {
/* STB low -> active CAN phy */
@@ -232,7 +208,6 @@ static const led_t i2l[] = {
led(9, fw_update_timeout, 31, 0, 0, 2),
led(a, fw_update_invalid_crc, 31, 0, 0, 4),
led(b, jump_to_app, 0, 63, 0, 10),
led(c, hardware_failure, 31, 0, 0, 10),
};
@@ -10,8 +10,6 @@ set(uavcanblid_hw_version_major 0)
set(uavcanblid_hw_version_minor 34)
set(uavcanblid_name "\"org.nxp.ucans32k146\"")
set(uavcanbl_padding 8)
add_definitions(
-DHW_UAVCAN_NAME=${uavcanblid_name}
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
@@ -79,7 +79,6 @@ SECTIONS
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
KEEP(*(.app_descriptor))
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
-150
View File
@@ -1,150 +0,0 @@
px4_add_board(
PLATFORM nuttx
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
UAVCAN_INTERFACES 2
UAVCAN_TIMER_OVERRIDE 6
CRYPTO sw_crypto
KEYSTORE stub_keystore
SERIAL_PORTS
GPS1:/dev/ttyS0
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
TEL4:/dev/ttyS3
DRIVERS
adc/ads1115
adc/board_adc
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
heater
#imu # all available imu drivers
imu/analog_devices/adis16448
imu/bosch/bmi055
imu/invensense/icm20602
imu/invensense/icm20689
imu/invensense/icm20948 # required for ak09916 mag
irlock
lights # all available light drivers
lights/rgbled_pwm
magnetometer # all available magnetometer drivers
optical_flow # all available optical flow drivers
osd
pca9685
pca9685_pwm_out
power_monitor/ina226
#protocol_splitter
pwm_input
pwm_out_sim
pwm_out
px4io
rc_input
roboclaw
smart_battery/batmon
rpm
safety_button
telemetry # all available telemetry drivers
tone_alarm
uavcan
MODULES
airspeed_selector
attitude_estimator_q
battery_status
camera_feedback
commander
dataman
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
gyro_calibration
gyro_fft
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih
temperature_compensation
uuv_att_control
uuv_pos_control
vmount
vtol_att_control
SYSTEMCMDS
bl_update
dmesg
dumpfile
esc_calib
gpio
hardfault_log
i2cdetect
led_control
mft
mixer
motor_ramp
motor_test
mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
serial_test
system_time
top
topic_listener
tune_control
uorb
usb_connected
ver
work_queue
EXAMPLES
fake_gps
#fake_imu
#fake_magnetometer
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
#hello
#hwtest # Hardware test
#matlab_csv_serial
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
#rover_steering_control # Rover example app
#uuv_example_app
#work_item
)
# For testing crypto with the stub_keystore, set keys to the PX4 test keys,
# for any real target using that keystore, these would probably be set as environment
# variables in the build environment
# Key 0: The firmware signature check key (public key), used by bootloaders
# NOTE: for FMUv5 this is not really used, it is only for NuttX based bootloaders
set(ENV{PUBLIC_KEY0} "${CMAKE_SOURCE_DIR}/Tools/test_keys/key0.pub")
# Key 1: An RSA2048 public key, used currently for logfile symmetric key exchange
set(ENV{PUBLIC_KEY1} "${CMAKE_SOURCE_DIR}/Tools/test_keys/rsa2048.pub")
# FW Signing tool, using ed25519 (this uses by default the key in Tools/test_keys/test_keys.json)
set(ENV{SIGNING_TOOL} "${CMAKE_SOURCE_DIR}/Tools/cryptotools.py")
@@ -1,244 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32f7"
CONFIG_ARCH_CHIP_STM32F765II=y
CONFIG_ARCH_CHIP_STM32F7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=22114
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x0032
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_VENDORSTR="3D Robotics"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_CRYPTO=y
CONFIG_CRYPTO_RANDOM_POOL=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=3
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAMTRON_WRITEWAIT=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32F7_ADC1=y
CONFIG_STM32F7_BBSRAM=y
CONFIG_STM32F7_BBSRAM_FILES=5
CONFIG_STM32F7_BKPSRAM=y
CONFIG_STM32F7_DMA1=y
CONFIG_STM32F7_DMA2=y
CONFIG_STM32F7_DMACAPABLE=y
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
CONFIG_STM32F7_I2C1=y
CONFIG_STM32F7_I2C2=y
CONFIG_STM32F7_I2C3=y
CONFIG_STM32F7_I2C4=y
CONFIG_STM32F7_I2C_DYNTIMEO=y
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32F7_OTGFS=y
CONFIG_STM32F7_PROGMEM=y
CONFIG_STM32F7_PWR=y
CONFIG_STM32F7_RTC=y
CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
CONFIG_STM32F7_RTC_MAGIC_REG=1
CONFIG_STM32F7_SAVE_CRASHDUMP=y
CONFIG_STM32F7_SDMMC1=y
CONFIG_STM32F7_SDMMC_DMA=y
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32F7_SPI1=y
CONFIG_STM32F7_SPI1_DMA=y
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
CONFIG_STM32F7_SPI2=y
CONFIG_STM32F7_SPI4=y
CONFIG_STM32F7_SPI5=y
CONFIG_STM32F7_SPI6=y
CONFIG_STM32F7_SPI_DMA=y
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
CONFIG_STM32F7_TIM10=y
CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y
CONFIG_STM32F7_USART_BREAKS=y
CONFIG_STM32F7_USART_INVERT=y
CONFIG_STM32F7_USART_SINGLEWIRE=y
CONFIG_STM32F7_USART_SWAP=y
CONFIG_STM32F7_WWDG=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
-1
View File
@@ -41,7 +41,6 @@ px4_add_board(
pca9685_pwm_out
power_monitor/ina226
power_monitor/ina228
power_monitor/ina238
#protocol_splitter
pwm_input
pwm_out_sim
@@ -3,7 +3,6 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1
-7
View File
@@ -19,13 +19,6 @@ then
ina228 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA238 1
then
# Start Digital power monitors
ina238 -X -b 1 -t 1 -k start
ina238 -X -b 2 -t 2 -k start
fi
if ver hwtypecmp V5X90 V5X91 V5X92 V5Xa0 V5Xa1 V5Xa2
then
#SKYNODE base fmu board orientation
-1
View File
@@ -42,7 +42,6 @@ px4_add_board(
pca9685_pwm_out
power_monitor/ina226
power_monitor/ina228
power_monitor/ina238
#protocol_splitter
pwm_out_sim
pwm_out
+1 -2
View File
@@ -3,8 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1
safety_button start
safety_button start
-7
View File
@@ -18,13 +18,6 @@ then
ina228 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA238 1
then
# Start Digital power monitors
ina238 -X -b 1 -t 1 -k start
ina238 -X -b 2 -t 2 -k start
fi
# Internal SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
-1
View File
@@ -277,7 +277,6 @@ function(px4_add_board)
if(CRYPTO)
set(PX4_CRYPTO ${CRYPTO} CACHE STRING "PX4 crypto implementation" FORCE)
add_definitions(-DPX4_CRYPTO)
endif()
if(KEYSTORE)
+20 -110
View File
@@ -62,120 +62,30 @@ function(px4_add_git_submodule)
REQUIRED TARGET PATH
ARGN ${ARGN})
option(GIT_SUBMODULE "Check submodules during build" ON)
set(REL_PATH)
# ENV GIT_SUBMODULES_ARE_EVIL
# ENV TERM_PROGRAM="vscode"
# ENV VSCODE_GIT_ASKPASS_MAIN
# ENV VSCODE_GIT_ASKPASS_NODE
# ENV VSCODE_GIT_IPC_HANDLE
# ENV VSCODE_IPC_HOOK_CLI
# if CI or vscode then force submodule update?
if(DEFINED ENV{VSCODE_IPC_HOOK_CLI})
#message(STATUS "VSCODE_IPC_HOOK_CLI: $ENV{VSCODE_IPC_HOOK_CLI}")
#message(STATUS "TERM_PROGRAM: $ENV{TERM_PROGRAM}")
#message(STATUS "VSCODE_GIT_ASKPASS_MAIN: $ENV{VSCODE_GIT_ASKPASS_MAIN}")
#message(STATUS "VSCODE_GIT_ASKPASS_NODE: $ENV{VSCODE_GIT_ASKPASS_NODE}")
#message(STATUS "VSCODE_GIT_IPC_HANDLE: $ENV{VSCODE_GIT_IPC_HANDLE}")
if(IS_ABSOLUTE ${PATH})
file(RELATIVE_PATH REL_PATH ${PX4_SOURCE_DIR} ${PATH})
else()
file(RELATIVE_PATH REL_PATH ${PX4_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/${PATH})
endif()
if(GIT_FOUND AND GIT_SUBMODULE AND NOT DEFINED ENV{GIT_SUBMODULES_ARE_EVIL})
execute_process(
COMMAND Tools/check_submodules.sh ${REL_PATH}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
set(REL_PATH)
string(REPLACE "/" "_" NAME ${PATH})
string(REPLACE "." "_" NAME ${NAME})
if(IS_ABSOLUTE ${PATH})
file(RELATIVE_PATH REL_PATH ${PX4_SOURCE_DIR} ${PATH})
else()
file(RELATIVE_PATH REL_PATH ${PX4_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/${PATH})
endif()
add_custom_command(OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/git_init_${NAME}.stamp
COMMAND Tools/check_submodules.sh ${REL_PATH}
COMMAND ${CMAKE_COMMAND} -E touch ${CMAKE_CURRENT_BINARY_DIR}/git_init_${NAME}.stamp
DEPENDS ${PX4_SOURCE_DIR}/.gitmodules ${PATH}/.git
COMMENT "git submodule ${REL_PATH}"
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
USES_TERMINAL
)
if(NOT EXISTS ${PATH}/.git)
execute_process(
COMMAND ${GIT_EXECUTABLE} submodule update --init --recursive --jobs=4 -- ${REL_PATH}
OUTPUT_VARIABLE GIT_SUBMODULE_UPDATE
RESULT_VARIABLE GIT_SUBMODULE_UPDATE_RESULT
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
if(NOT GIT_SUBMODULE_UPDATE_RESULT EQUAL "0")
message(FATAL_ERROR "git submodule update --init --recursive -- ${REL_PATH} failed: ${GIT_SUBMODULE_UPDATE}")
endif()
else()
execute_process(
COMMAND ${GIT_EXECUTABLE} submodule status -- ${REL_PATH}
OUTPUT_VARIABLE GIT_SUBMODULE_STATUS
RESULT_VARIABLE GIT_SUBMODULE_STATUS_RESULT
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
#message(STATUS "git submodule status ${REL_PATH} result ${GIT_SUBMODULE_STATUS_RESULT} : ${GIT_SUBMODULE_STATUS}")
if(NOT GIT_SUBMODULE_STATUS_RESULT EQUAL "0")
message(FATAL_ERROR "git submodule status -- ${REL_PATH} failed: ${GIT_SUBMODULE_STATUS}")
else()
# submodule status characters
string(FIND "${GIT_SUBMODULE_STATUS}" "+" submodule_plus)
string(FIND "${GIT_SUBMODULE_STATUS}" "-" submodule_minus)
string(FIND "${GIT_SUBMODULE_STATUS}" "U" submodule_merge_conflicts)
# + commit does not match the SHA-1 found in the index
if("${submodule_plus}" EQUAL 0)
# GIT_SHA_HEAD: submodule git SHA on current HEAD
execute_process(
COMMAND ${GIT_EXECUTABLE} ls-tree -d HEAD ${REL_PATH} | awk '{print $3;}
OUTPUT_VARIABLE GIT_SHA_HEAD
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
# GIT_SHA_PREV_HEAD: submodule git SHA on previous HEAD
execute_process(
COMMAND ${GIT_EXECUTABLE} ls-tree -d HEAD@{1} ${REL_PATH} | awk '{print $3;}
OUTPUT_VARIABLE GIT_SHA_PREV_HEAD
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
#message(STATUS "GIT_SHA_HEAD: ${GIT_SHA_HEAD}")
#message(STATUS "GIT_SHA_PREV_HEAD: ${GIT_SHA_PREV_HEAD}")
# TODO: check if submodule is dirty?
if(${GIT_SHA_HEAD} MATCHES ${GIT_SHA_PREV_HEAD})
#message(STATUS "${rel_path} GIT SHA matched previous")
# submodule hasn't changed, assume it's safe to update
execute_process(
COMMAND ${GIT_EXECUTABLE} submodule update --init --recursive --jobs=4 -- ${REL_PATH}
OUTPUT_VARIABLE GIT_SUBMODULE_UPDATE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
else()
message(NOTICE "submodule ${REL_PATH} commit does not match the SHA-1 found in the index")
endif()
endif()
# - uninitialized
if("${submodule_minus}" EQUAL 0)
execute_process(
COMMAND ${GIT_EXECUTABLE} submodule update --init --recursive --jobs=4 -- ${REL_PATH}
OUTPUT_VARIABLE GIT_SUBMODULE_UPDATE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
endif()
# U merge conflicts
if("${submodule_merge_conflicts}" EQUAL 0)
message(NOTICE "submodule ${REL_PATH} has merge conflicts")
endif()
endif()
endif()
add_custom_target(${TARGET})
set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS ${PATH}/.git)
endif()
add_custom_target(${TARGET} DEPENDS git_init_${NAME}.stamp)
endfunction()
+1 -1
View File
@@ -4,4 +4,4 @@ uint64 timestamp_utc # UTC timestamp
uint32 seq # Image sequence number
bool feedback # Trigger feedback from camera
# TOPICS camera_trigger
# TOPICS camera_trigger camera_trigger_secondary
-1
View File
@@ -23,7 +23,6 @@ uint64 timestamp_last_signal # last valid reception time
uint8 channel_count # number of channels actually being seen
int8 RSSI_MAX = 100
int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception
bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly.
+7
View File
@@ -26,4 +26,11 @@ uint8 kill_switch # throttle kill: _NORMAL_, KILL
uint8 gear_switch # landing gear switch: _DOWN_, UP
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
# legacy "advanced" switch configuration (will be removed soon)
uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
uint8 man_switch # manual switch (only relevant for fixed wings, optional): _STABILIZED_, MANUAL
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
uint8 stab_switch # stabilize switch (only relevant for fixed wings, optional): _MANUAL, STABILIZED
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
uint32 switch_changes # number of switch changes
+27 -16
View File
@@ -6,38 +6,49 @@ float32 voltage_v # Servo rail voltage in volts
float32 rssi_v # RSSI pin voltage in volts
# PX4IO status flags (PX4IO_P_STATUS_FLAGS)
bool status_arm_sync
bool status_failsafe
bool status_fmu_initialized
bool status_fmu_ok
bool status_init_ok
bool status_outputs_armed
bool status_raw_pwm
bool status_override
bool status_rc_ok
bool status_rc_dsm
bool status_rc_ppm
bool status_rc_dsm
bool status_rc_sbus
bool status_fmu_ok
bool status_raw_pwm
bool status_mixer_ok
bool status_arm_sync
bool status_init_ok
bool status_failsafe
bool status_safety_off
bool status_fmu_initialized
bool status_rc_st24
bool status_rc_sumd
bool status_safety_off
# PX4IO alarms (PX4IO_P_STATUS_ALARMS)
bool alarm_pwm_error
bool alarm_vbatt_low
bool alarm_temperature
bool alarm_servo_current
bool alarm_acc_current
bool alarm_fmu_lost
bool alarm_rc_lost
bool alarm_pwm_error
bool alarm_vservo_fault
# PX4IO arming (PX4IO_P_SETUP_ARMING)
bool arming_failsafe_custom
bool arming_io_arm_ok
bool arming_fmu_armed
bool arming_fmu_prearmed
bool arming_force_failsafe
bool arming_io_arm_ok
bool arming_manual_override_ok
bool arming_failsafe_custom
bool arming_inair_restart_ok
bool arming_always_pwm_enable
bool arming_rc_handling_disabled
bool arming_lockdown
bool arming_force_failsafe
bool arming_termination_failsafe
bool arming_override_immediate
uint16[8] pwm
uint16[8] pwm_disarmed
uint16[8] pwm_failsafe
uint16[8] pwm_rate_hz
int16[8] actuators
uint16[8] servos
uint16[18] raw_inputs
+27 -30
View File
@@ -1,39 +1,36 @@
uint64 timestamp # time since system start (microseconds)
uint8 FUNCTION_THROTTLE = 0
uint8 FUNCTION_ROLL = 1
uint8 FUNCTION_PITCH = 2
uint8 FUNCTION_YAW = 3
uint8 FUNCTION_RETURN = 4
uint8 FUNCTION_LOITER = 5
uint8 FUNCTION_OFFBOARD = 6
uint8 FUNCTION_FLAPS = 7
uint8 FUNCTION_AUX_1 = 8
uint8 FUNCTION_AUX_2 = 9
uint8 FUNCTION_AUX_3 = 10
uint8 FUNCTION_AUX_4 = 11
uint8 FUNCTION_AUX_5 = 12
uint8 FUNCTION_AUX_6 = 13
uint8 FUNCTION_PARAM_1 = 14
uint8 FUNCTION_PARAM_2 = 15
uint8 FUNCTION_PARAM_3_5 = 16
uint8 FUNCTION_KILLSWITCH = 17
uint8 FUNCTION_TRANSITION = 18
uint8 FUNCTION_GEAR = 19
uint8 FUNCTION_ARMSWITCH = 20
uint8 FUNCTION_FLTBTN_SLOT_1 = 21
uint8 FUNCTION_FLTBTN_SLOT_2 = 22
uint8 FUNCTION_FLTBTN_SLOT_3 = 23
uint8 FUNCTION_FLTBTN_SLOT_4 = 24
uint8 FUNCTION_FLTBTN_SLOT_5 = 25
uint8 FUNCTION_FLTBTN_SLOT_6 = 26
uint8 FUNCTION_FLTBTN_SLOT_COUNT = 6
uint8 FUNCTION_THROTTLE = 0
uint8 FUNCTION_ROLL = 1
uint8 FUNCTION_PITCH = 2
uint8 FUNCTION_YAW = 3
uint8 FUNCTION_MODE = 4
uint8 FUNCTION_RETURN = 5
uint8 FUNCTION_POSCTL = 6
uint8 FUNCTION_LOITER = 7
uint8 FUNCTION_OFFBOARD = 8
uint8 FUNCTION_ACRO = 9
uint8 FUNCTION_FLAPS = 10
uint8 FUNCTION_AUX_1 = 11
uint8 FUNCTION_AUX_2 = 12
uint8 FUNCTION_AUX_3 = 13
uint8 FUNCTION_AUX_4 = 14
uint8 FUNCTION_AUX_5 = 15
uint8 FUNCTION_PARAM_1 = 16
uint8 FUNCTION_PARAM_2 = 17
uint8 FUNCTION_PARAM_3_5 = 18
uint8 FUNCTION_KILLSWITCH = 19
uint8 FUNCTION_TRANSITION = 20
uint8 FUNCTION_GEAR = 21
uint8 FUNCTION_ARMSWITCH = 22
uint8 FUNCTION_STAB = 23
uint8 FUNCTION_AUX_6 = 24
uint8 FUNCTION_MAN = 25
uint64 timestamp_last_valid # Timestamp of last valid RC signal
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
uint8 channel_count # Number of valid channels
int8[27] function # Functions mapping
int8[26] function # Functions mapping
uint8 rssi # Receive signal strength index
bool signal_lost # Control signal lost, should be checked together with topic timeout
uint32 frame_drop_count # Number of dropped frames
+2
View File
@@ -1,3 +1,5 @@
uint64 timestamp # time since system start (microseconds)
bool safety_switch_available # Set to true if a safety switch is connected
bool safety_off # Set to true if safety is off
bool override_available # Set to true if external override system is connected
bool override_enabled # Set to true if override is engaged
+1
View File
@@ -1,6 +1,7 @@
uint64 timestamp # time since system start (microseconds)
bool flag_armed # synonym for actuator_armed.armed
bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing
bool flag_multicopter_position_control_enabled
bool flag_control_manual_enabled # true if manual input is mixed in
-1
View File
@@ -1,5 +1,4 @@
# Fused local position in NED.
# The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
+1
View File
@@ -27,6 +27,7 @@ bool circuit_breaker_engaged_usb_check
bool circuit_breaker_engaged_posfailure_check # set to true when the position valid checks have been disabled
bool circuit_breaker_vtol_fw_arming_check # set to true if for VTOLs arming in fixed-wing mode should be allowed
bool offboard_control_signal_found_once
bool offboard_control_signal_lost
bool rc_signal_found_once
@@ -1,219 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#ifdef PX4_CRYPTO
#include <stdbool.h>
#include <stdint.h>
#include <px4_random.h>
#include <px4_platform_common/crypto_algorithms.h>
#include <px4_platform_common/sem.h>
#include "crypto_backend_definitions.h"
/*
* Crypto API interface class
*/
class PX4Crypto
{
public:
/*
* Constructor & destructor
*/
PX4Crypto();
~PX4Crypto();
/*
* Class function for crypto api initialization, called only once at
* boot
*/
static void px4_crypto_init(void);
/*
* Open crypto API for a specific algorithm
* algorithm: The crypto algorithm to be used
* returns true on success, false on failure
*/
bool open(px4_crypto_algorithm_t algorithm);
/*
* Close the crypto API. Optional, it is also closed by destructing the
* interface object
*/
void close();
/*
* Keystore access functions
*/
/*
* Generate a single random key for symmetric-key encryption
*
* idx: the index in keystore where the key will be stored
* persistent: whether the key need to be stored persistently
* returns true on success, false on failure
*/
bool generate_key(uint8_t idx,
bool persistent);
/*
* Generate a key pair for asymmetric-key encryption
*
* algorithm: the key type
* key_size: size of the key in bytes
* private_idx: the private key will be stored in this index in the keystore
* public_idx: the public key will be stored in this index in the keystore
* persistent: whether the keys need to be stored persistently
* returns true on success, false on failure
*/
bool generate_keypair(size_t key_size,
uint8_t private_idx,
uint8_t public_idx,
bool persistent);
/*
* Re-create or set nonce.
*
* A nonce or intialization vector value for the selected algortithm is
* automatically generated when the crypto session is opened. If needed, the
* nonce can be set by this function.
* If this is called with NULL pointer, a new nonce is automatically random
* generated
*/
bool renew_nonce(const uint8_t *nonce, size_t nonce_size);
/*
* Get current crypto session nonce
*
* This function returns the current nonce for the session
* If the "nonce" is NULL, only nonse legth will be provided
* nonce: pointer to the buffer where the nonce will be written
* nonce_len: length of the current nonce vector for the session
* returns true on success, false on failure
*/
bool get_nonce(uint8_t *nonce,
size_t *nonce_len);
/*
* Store a key into keystore
*
* encryption_idx: The key index in keystore to be used in decrypting and
* authenticating the key before storing
* key: The pointer to the key
* key_idx: Index where the key will be stored in keystore
*/
bool set_key(uint8_t encryption_idx,
const uint8_t *key,
uint8_t key_idx);
/*
* Get a key from keystore. Key can be encrypted
*
* key_idx: Index of the requested key in the keystore
* key: The provided buffer to the key. If NULL, the function only provides
* the length of the key.
* key_len: input: the size of the provided "key" buffer.
output: the actual size of the key
* encryption_key_idx: The key index in keystore to be used for encrypting
* returns true on success, false on failure
*
*/
bool get_encrypted_key(uint8_t key_idx,
uint8_t *key,
size_t *key_len,
uint8_t encryption_key_idx);
/*
* PX4 Crypto API functions
*/
/*
* Verify signature
*
* key_index: public key index in keystore
* signature: pointer to the signature
* message: pointer to the data to be verified
* message_size: size of the message in bytes
*/
bool signature_check(uint8_t key_index,
const uint8_t *signature,
const uint8_t *message,
size_t message_size);
/*
* Encrypt data. This always supports encryption in-place
*
* key_index: key index in keystore
* message: pointer to the message
* message_size: size of the message in bytes
* cipher: pointer to a buffer for encrypted data
* cipher_size: size of the buffer reserved for cipher and actual cipher length
* after the encryption
* returns true on success, false on failure
*/
bool encrypt_data(uint8_t key_index,
const uint8_t *message,
size_t message_size,
uint8_t *cipher,
size_t *cipher_size);
size_t get_min_blocksize(uint8_t key_idx);
private:
crypto_session_handle_t _crypto_handle;
static px4_sem_t _lock;
static bool _initialized;
static void lock() { do {} while (px4_sem_wait(&PX4Crypto::_lock) != 0); }
static void unlock() { px4_sem_post(&PX4Crypto::_lock); }
};
#endif
@@ -71,16 +71,6 @@ void keystore_close(keystore_session_handle_t *handle);
*/
size_t keystore_get_key(keystore_session_handle_t handle, uint8_t idx, uint8_t *key_buf, size_t key_buf_size);
/*
* Store a key persistently into the keystore
* handle: a handle to an open keystore
* idx: key index in keystore
* key: pointer to the key
* key_size: size of the key
*/
bool keystore_put_key(keystore_session_handle_t handle, uint8_t idx, uint8_t *key, size_t key_size);
/*
* Architecture specific PX4 Crypto API functions
*/
@@ -106,48 +96,6 @@ crypto_session_handle_t crypto_open(px4_crypto_algorithm_t algorithm);
void crypto_close(crypto_session_handle_t *handle);
/*
* Generate a key
* handle: Open handle for the crypto session. The key will be generated for
* the crypto algorithm used by this session
* idx: The key index, by which the key can be used
* persistent: if set to "true", the key will be stored into the keystore
*/
bool crypto_generate_key(crypto_session_handle_t handle,
uint8_t idx,
bool persistent);
/*
* Get a key from keystore, possibly encrypted
*
* handle: an open crypto context; the returned key will be encrypted
* according to this context
* key_idx: Index of the requested key in the keystore
* key: The provided buffer to the key
* max_len: the length of the provided key buffer. Returns the actual key size
* encryption_key_idx: The key index in keystore to be used for encrypting
* returns true on success, false on failure
*/
bool crypto_get_encrypted_key(crypto_session_handle_t handle,
uint8_t key_idx,
uint8_t *key,
size_t *max_len,
uint8_t encryption_key_idx);
/*
* Get the generated nonce value
*
* handle: an open crypto context; the returned nonce is the one associsated
* with this context/algorithm
* nonce: The provided buffer to the key. If NULL, only length is returned
* nonce_len: the length of the nonce value
* encryption_key_idx: The key index in keystore to be used for encrypting
* returns true on success, false on failure
*/
bool crypto_get_nonce(crypto_session_handle_t handle,
uint8_t *nonce,
size_t *nonce_len);
/*
* Perform signature check using an open session to crypto
* handle: session handle, returned by open
@@ -162,25 +110,6 @@ bool crypto_signature_check(crypto_session_handle_t handle,
const uint8_t *message,
size_t message_size);
bool crypto_encrypt_data(crypto_session_handle_t handle,
uint8_t key_index,
const uint8_t *message,
size_t message_size,
uint8_t *cipher,
size_t *cipher_size);
/*
* Returns a minimum data block size on which the crypto operations can be
* performed. Performing encryption on sizes which are not multiple of this
* are valid, but the output will be padded to the multiple of this value
* Input for decryption must be multiple of this value.
* handle: session handle, returned by open
* key_idx: key to be used for encryption/decryption
* returs the block size
*/
size_t crypto_get_min_blocksize(crypto_session_handle_t handle, uint8_t key_idx);
#if defined(__cplusplus)
} // extern "C"
#endif
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019-2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2019-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
@@ -77,16 +77,16 @@ static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -18};
static constexpr wq_config_t uavcan{"wq:uavcan", 3624, -19};
static constexpr wq_config_t UART0{"wq:UART0", 1632, -21};
static constexpr wq_config_t UART1{"wq:UART1", 1632, -22};
static constexpr wq_config_t UART2{"wq:UART2", 1632, -23};
static constexpr wq_config_t UART3{"wq:UART3", 1632, -24};
static constexpr wq_config_t UART4{"wq:UART4", 1632, -25};
static constexpr wq_config_t UART5{"wq:UART5", 1632, -26};
static constexpr wq_config_t UART6{"wq:UART6", 1632, -27};
static constexpr wq_config_t UART7{"wq:UART7", 1632, -28};
static constexpr wq_config_t UART8{"wq:UART8", 1632, -29};
static constexpr wq_config_t UART_UNKNOWN{"wq:UART_UNKNOWN", 1632, -30};
static constexpr wq_config_t UART0{"wq:UART0", 1536, -21};
static constexpr wq_config_t UART1{"wq:UART1", 1536, -22};
static constexpr wq_config_t UART2{"wq:UART2", 1536, -23};
static constexpr wq_config_t UART3{"wq:UART3", 1536, -24};
static constexpr wq_config_t UART4{"wq:UART4", 1536, -25};
static constexpr wq_config_t UART5{"wq:UART5", 1536, -26};
static constexpr wq_config_t UART6{"wq:UART6", 1536, -27};
static constexpr wq_config_t UART7{"wq:UART7", 1536, -28};
static constexpr wq_config_t UART8{"wq:UART8", 1536, -29};
static constexpr wq_config_t UART_UNKNOWN{"wq:UART_UNKNOWN", 1536, -30};
static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50};
@@ -37,5 +37,6 @@ typedef struct {
int handle;
} keystore_session_handle_t;
static inline void keystore_session_handle_init(keystore_session_handle_t *handle) {handle->handle = 0;}
static inline bool keystore_session_handle_valid(keystore_session_handle_t handle) {return handle.handle > 0;}
/* For the stub_keystore the handle is not used at the moment, so it is always valid */
inline bool keystore_session_handle_valid(keystore_session_handle_t handle) {return handle.handle > 0;}
@@ -77,8 +77,3 @@ size_t keystore_get_key(keystore_session_handle_t handle, uint8_t idx, uint8_t *
return ret;
}
bool keystore_put_key(keystore_session_handle_t handle, uint8_t idx, uint8_t *key, size_t key_size)
{
return false;
}
@@ -41,9 +41,8 @@ target_link_libraries(crypto_backend
target_link_libraries(crypto_backend
PRIVATE
px4_random
monocypher
libtomcrypt
)
target_include_directories(crypto_backend PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
@@ -42,11 +42,7 @@
#include <stdbool.h>
#include <px4_platform_common/crypto_backend.h>
#include <px4_random.h>
#include <lib/crypto/monocypher/src/optional/monocypher-ed25519.h>
#include <tomcrypt.h>
extern void libtomcrypt_init(void);
/* room for 16 keys */
#define KEY_CACHE_LEN 16
@@ -71,11 +67,6 @@ typedef struct {
static volatile_key_t key_cache[KEY_CACHE_LEN];
typedef struct {
uint8_t nonce[24];
uint64_t ctr;
} chacha20_context_t;
/* Clear key cache */
static void clear_key_cache(void)
{
@@ -135,43 +126,19 @@ void crypto_init()
{
keystore_init();
clear_key_cache();
libtomcrypt_init();
}
crypto_session_handle_t crypto_open(px4_crypto_algorithm_t algorithm)
{
crypto_session_handle_t ret;
ret.algorithm = algorithm;
ret.keystore_handle = keystore_open();
if (keystore_session_handle_valid(ret.keystore_handle)) {
ret.algorithm = algorithm;
ret.handle = ++crypto_open_count;
} else {
ret.handle = 0;
ret.context = NULL;
ret.algorithm = CRYPTO_NONE;
return ret;
}
switch (algorithm) {
case CRYPTO_XCHACHA20: {
chacha20_context_t *context = malloc(sizeof(chacha20_context_t));
if (!context) {
ret.handle = 0;
crypto_open_count--;
} else {
ret.context = context;
px4_get_secure_random(context->nonce, sizeof(context->nonce));
context->ctr = 0;
}
}
break;
default:
ret.context = NULL;
}
return ret;
@@ -179,17 +146,9 @@ crypto_session_handle_t crypto_open(px4_crypto_algorithm_t algorithm)
void crypto_close(crypto_session_handle_t *handle)
{
// Not open?
if (!crypto_session_handle_valid(*handle)) {
return;
}
crypto_open_count--;
handle->handle = 0;
keystore_close(&handle->keystore_handle);
free(handle->context);
handle->context = NULL;
}
bool crypto_signature_check(crypto_session_handle_t handle,
@@ -200,13 +159,13 @@ bool crypto_signature_check(crypto_session_handle_t handle,
{
bool ret = false;
size_t keylen = 0;
const uint8_t *public_key = NULL;
const uint8_t *public_key;
if (crypto_session_handle_valid(handle)) {
public_key = crypto_get_key_ptr(handle.keystore_handle, key_index, &keylen);
}
if (keylen == 0 || public_key == NULL) {
if (keylen == 0) {
return false;
}
@@ -221,212 +180,3 @@ bool crypto_signature_check(crypto_session_handle_t handle,
return ret;
}
bool crypto_encrypt_data(crypto_session_handle_t handle,
uint8_t key_idx,
const uint8_t *message,
size_t message_size,
uint8_t *cipher,
size_t *cipher_size)
{
bool ret = false;
if (!crypto_session_handle_valid(handle)) {
return ret;
}
switch (handle.algorithm) {
case CRYPTO_NONE:
if (*cipher_size >= message_size) {
/* In-place there is no copy needed */
if (message != cipher) {
memcpy(cipher, message, message_size);
}
*cipher_size = message_size;
ret = true;
}
break;
case CRYPTO_XCHACHA20: {
size_t key_sz;
uint8_t *key = (uint8_t *)crypto_get_key_ptr(handle.keystore_handle, key_idx, &key_sz);
chacha20_context_t *context = handle.context;
if (key_sz == 32) {
context->ctr = crypto_xchacha20_ctr(cipher, message, *cipher_size, key, context->nonce, context->ctr);
ret = true;
}
}
break;
case CRYPTO_RSA_OAEP: {
rsa_key key;
size_t key_sz;
unsigned long outlen = *cipher_size;
uint8_t *public_key = (uint8_t *)crypto_get_key_ptr(handle.keystore_handle, key_idx, &key_sz);
*cipher_size = 0;
if (public_key &&
rsa_import(public_key, key_sz, &key) == CRYPT_OK) {
if (outlen >= ltc_mp.unsigned_size(key.N) &&
pkcs_1_oaep_encode(message, message_size,
NULL, 0,
ltc_mp.count_bits(key.N),
NULL,
0, 0,
cipher, &outlen) == CRYPT_OK &&
ltc_mp.rsa_me(cipher, outlen, cipher, &outlen, PK_PUBLIC, &key) == CRYPT_OK) {
*cipher_size = outlen;
ret = true;
}
rsa_free(&key);
}
}
break;
default:
break;
}
return ret;
}
bool crypto_generate_key(crypto_session_handle_t handle,
uint8_t idx, bool persistent)
{
bool ret = false;
if (idx >= KEY_CACHE_LEN) {
return false;
}
switch (handle.algorithm) {
case CRYPTO_XCHACHA20:
if (key_cache[idx].key_size < 32) {
if (key_cache[idx].key_size > 0) {
SECMEM_FREE(key_cache[idx].key);
key_cache[idx].key_size = 0;
}
key_cache[idx].key = SECMEM_ALLOC(32);
}
if (key_cache[idx].key) {
key_cache[idx].key_size = 32;
px4_get_secure_random(key_cache[idx].key, 32);
ret = true;
} else {
key_cache[idx].key_size = 0;
}
break;
default:
break;
}
if (ret && persistent) {
keystore_put_key(handle.keystore_handle, idx, key_cache[idx].key, key_cache[idx].key_size);
}
return ret;
}
bool crypto_get_encrypted_key(crypto_session_handle_t handle,
uint8_t key_idx,
uint8_t *key,
size_t *max_len,
uint8_t encryption_key_idx)
{
// Retrieve the plaintext key
bool ret = true;
size_t key_sz;
const uint8_t *plain_key = crypto_get_key_ptr(handle.keystore_handle, key_idx, &key_sz);
if (key_sz == 0) {
return false;
}
// Encrypt it
if (key != NULL) {
ret = crypto_encrypt_data(handle,
encryption_key_idx,
plain_key,
key_sz,
key,
max_len);
} else {
// The key size, encrypted, is a multiple of minimum block size for the algorithm+key
size_t min_block = crypto_get_min_blocksize(handle, encryption_key_idx);
*max_len = key_sz / min_block * min_block;
if (key_sz % min_block) {
*max_len += min_block;
}
}
return ret;
}
bool crypto_get_nonce(crypto_session_handle_t handle,
uint8_t *nonce,
size_t *nonce_len)
{
switch (handle.algorithm) {
case CRYPTO_XCHACHA20: {
chacha20_context_t *context = handle.context;
if (nonce != NULL && context != NULL) {
memcpy(nonce, context->nonce, sizeof(context->nonce));
}
*nonce_len = sizeof(context->nonce);
}
break;
default:
*nonce_len = 0;
}
return true;
}
size_t crypto_get_min_blocksize(crypto_session_handle_t handle, uint8_t key_idx)
{
size_t ret;
switch (handle.algorithm) {
case CRYPTO_XCHACHA20:
ret = 64;
break;
case CRYPTO_RSA_OAEP: {
rsa_key enc_key;
unsigned pub_key_sz;
uint8_t *pub_key = (uint8_t *)crypto_get_key_ptr(handle.keystore_handle, key_idx, &pub_key_sz);
if (pub_key &&
rsa_import(pub_key, pub_key_sz, &enc_key) == CRYPT_OK) {
ret = ltc_mp.unsigned_size(enc_key.N);
rsa_free(&enc_key);
} else {
ret = 0;
}
}
break;
default:
ret = 1;
}
return ret;
}
@@ -39,9 +39,8 @@
typedef struct {
int handle;
px4_crypto_algorithm_t algorithm;
uint8_t *nonce;
keystore_session_handle_t keystore_handle;
void *context;
} crypto_session_handle_t;
static inline void crypto_session_handle_init(crypto_session_handle_t *handle) {handle->handle = 0;}
static inline bool crypto_session_handle_valid(crypto_session_handle_t handle) {return handle.handle > 0 && keystore_session_handle_valid(handle.keystore_handle);}
static inline bool crypto_session_handle_valid(crypto_session_handle_t handle) {return handle.handle > 0;}
+2 -10
View File
@@ -369,9 +369,7 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
if (!quit) {
// update the stats
int total_size = 0;
int total_msgs = 0;
//update the stats
hrt_abstime current_time = hrt_absolute_time();
float dt = (current_time - start_time) / 1.e6f;
cur_node = first_node;
@@ -380,10 +378,6 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
unsigned int num_msgs = cur_node->node->updates_available(cur_node->last_pub_msg_count);
cur_node->pub_msg_delta = roundf(num_msgs / dt);
cur_node->last_pub_msg_count += num_msgs;
total_size += cur_node->pub_msg_delta * cur_node->node->get_meta()->o_size;
total_msgs += cur_node->pub_msg_delta;
cur_node = cur_node->next;
}
@@ -394,8 +388,7 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
PX4_INFO_RAW("\033[H"); // move cursor to top left corner
}
PX4_INFO_RAW(CLEAR_LINE "update: 1s, topics: %i, total publications: %i, %.1f kB/s\n",
num_topics, total_msgs, (double)(total_size / 1000.f));
PX4_INFO_RAW(CLEAR_LINE "update: 1s, num topics: %i\n", num_topics);
PX4_INFO_RAW(CLEAR_LINE "%-*s INST #SUB RATE #Q SIZE\n", (int)max_topic_name_length - 2, "TOPIC NAME");
cur_node = first_node;
@@ -411,7 +404,6 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
cur_node = cur_node->next;
}
if (!only_once) {
PX4_INFO_RAW("\033[0J"); // clear the rest of the screen
}
@@ -83,7 +83,7 @@ int uORBTest::UnitTest::pubsublatency_main()
if (fds[0].revents & POLLIN) {
orb_copy(ORB_ID(orb_test_medium), test_multi_sub, &t);
unsigned elt = (unsigned)hrt_elapsed_time(&t.timestamp);
unsigned elt = (unsigned)hrt_elapsed_time_atomic(&t.timestamp);
latency_integral += elt;
timings[i] = elt;
-1
View File
@@ -94,7 +94,6 @@ list(APPEND nuttx_libs
nuttx_fs
nuttx_mm
nuttx_sched
nuttx_crypto
)
if (CONFIG_NET)
-1
View File
@@ -319,7 +319,6 @@ add_nuttx_dir(sched sched y -D__KERNEL__)
add_nuttx_dir(c libs/libc n "")
add_nuttx_dir(xx libs/libxx n "")
add_nuttx_dir(mm mm n "")
add_nuttx_dir(crypto crypto y -D__KERNEL__)
if(CONFIG_NET)
add_nuttx_dir(net net y -D__KERNEL__)
@@ -57,7 +57,6 @@ typedef enum {
fw_update_timeout,
fw_update_invalid_crc,
jump_to_app,
hardware_failure,
} uiindication_t;
#ifndef __ASSEMBLY__
+1 -13
View File
@@ -48,7 +48,6 @@ if(NOT PX4_BOARD MATCHES "io-v2")
px4_manifest.cpp
px4_mtd.cpp
px4_24xxxx_mtd.c
px4_crypto.cpp
)
target_link_libraries(px4_layer
PRIVATE
@@ -59,7 +58,7 @@ if(NOT PX4_BOARD MATCHES "io-v2")
nuttx_sched
px4_work_queue
uORB
)
)
else()
add_library(px4_layer ${PX4_SOURCE_DIR}/platforms/common/empty.c)
endif()
@@ -67,14 +66,3 @@ add_dependencies(px4_layer prebuild_targets)
add_subdirectory(gpio)
add_subdirectory(srgbled)
if (DEFINED PX4_CRYPTO)
add_library(px4_random nuttx_random.c)
add_dependencies(px4_random nuttx_context)
target_link_libraries(px4_random PRIVATE nuttx_crypto)
target_link_libraries(px4_layer
PUBLIC
crypto_backend
)
endif()
@@ -1,149 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#if defined(PX4_CRYPTO)
#include <px4_platform_common/crypto.h>
#include <px4_platform_common/crypto_backend.h>
extern "C" {
#include <nuttx/random.h>
}
px4_sem_t PX4Crypto::_lock;
bool PX4Crypto::_initialized = false;
void PX4Crypto::px4_crypto_init()
{
if (PX4Crypto::_initialized) {
return;
}
px4_sem_init(&PX4Crypto::_lock, 0, 1);
// Initialize nuttx random pool, if it is being used by crypto
#ifdef CONFIG_CRYPTO_RANDOM_POOL
up_randompool_initialize();
#endif
// initialize keystore functionality
keystore_init();
// initialize actual crypto algoritms
crypto_init();
PX4Crypto::_initialized = true;
}
PX4Crypto::PX4Crypto()
{
// Initialize an empty handle
crypto_session_handle_init(&_crypto_handle);
}
PX4Crypto::~PX4Crypto()
{
close();
}
bool PX4Crypto::open(px4_crypto_algorithm_t algorithm)
{
bool ret = false;
lock();
// HW specific crypto already open? Just close before proceeding
if (crypto_session_handle_valid(_crypto_handle)) {
crypto_close(&_crypto_handle);
}
// Open the HW specific crypto handle
_crypto_handle = crypto_open(algorithm);
if (crypto_session_handle_valid(_crypto_handle)) {
ret = true;
}
unlock();
return ret;
}
void PX4Crypto::close()
{
if (!crypto_session_handle_valid(_crypto_handle)) {
return;
}
lock();
crypto_close(&_crypto_handle);
unlock();
}
bool PX4Crypto::encrypt_data(uint8_t key_index,
const uint8_t *message,
size_t message_size,
uint8_t *cipher,
size_t *cipher_size)
{
return crypto_encrypt_data(_crypto_handle, key_index, message, message_size, cipher, cipher_size);
}
bool PX4Crypto::generate_key(uint8_t idx,
bool persistent)
{
return crypto_generate_key(_crypto_handle, idx, persistent);
}
bool PX4Crypto::get_nonce(uint8_t *nonce,
size_t *nonce_len)
{
return crypto_get_nonce(_crypto_handle, nonce, nonce_len);
}
bool PX4Crypto::get_encrypted_key(uint8_t key_idx,
uint8_t *key,
size_t *key_len,
uint8_t encryption_key_idx)
{
return crypto_get_encrypted_key(_crypto_handle, key_idx, key, key_len, encryption_key_idx);
}
size_t PX4Crypto::get_min_blocksize(uint8_t key_idx)
{
return crypto_get_min_blocksize(_crypto_handle, key_idx);
}
#endif
@@ -52,10 +52,6 @@
# include <nuttx/i2c/i2c_master.h>
#endif // CONFIG_I2C
#if defined(PX4_CRYPTO)
#include <px4_platform_common/crypto.h>
#endif
int px4_platform_init()
{
@@ -74,10 +70,6 @@ int px4_platform_init()
close(fd_buf);
}
#if defined(PX4_CRYPTO)
PX4Crypto::px4_crypto_init();
#endif
hrt_init();
param_init();
@@ -586,6 +586,21 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
ts->tv_nsec = abstime * 1000;
}
/**
* Compare a time value with the current time as atomic operation.
*/
hrt_abstime
hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
{
irqstate_t flags = px4_enter_critical_section();
hrt_abstime delta = hrt_absolute_time() - *then;
px4_leave_critical_section(flags);
return delta;
}
/**
* Store the absolute time in an interrupt-safe fashion
*/
@@ -87,6 +87,10 @@ __BEGIN_DECLS
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define kinetis_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet
#define px4_savepanic(fileno, context, length) kinetis_bbsram_savepanic(fileno, context, length)
/* bus_num is zero based on kinetis and must be translated from the legacy one based */
#define PX4_BUS_OFFSET 1 /* Kinetis buses are 0 based and adjustment is needed */
@@ -598,6 +598,21 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
ts->tv_nsec = abstime * 1000;
}
/**
* Compare a time value with the current time as atomic operation.
*/
hrt_abstime
hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
{
irqstate_t flags = px4_enter_critical_section();
hrt_abstime delta = hrt_absolute_time() - *then;
px4_leave_critical_section(flags);
return delta;
}
/**
* Store the absolute time in an interrupt-safe fashion
*/
@@ -82,6 +82,10 @@ __BEGIN_DECLS
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define imxrt_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet
#define px4_savepanic(fileno, context, length) imxrt_bbsram_savepanic(fileno, context, length)
/* bus_num is 1 based on imx and must be translated from the legacy one based */
#define PX4_BUS_OFFSET 0 /* imxrt buses are 1 based no adjustment needed */
@@ -89,6 +89,10 @@ __BEGIN_DECLS
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define s32k1xx_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet
#define px4_savepanic(fileno, context, length) s32k1xx_bbsram_savepanic(fileno, context, length)
/* bus_num is zero based on s32k1xx and must be translated from the legacy one based */
#define PX4_BUS_OFFSET 1 /* s32k1xx buses are 0 based and adjustment is needed */
@@ -634,6 +634,21 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
ts->tv_nsec = abstime * 1000;
}
/**
* Compare a time value with the current time as atomic operation.
*/
hrt_abstime
hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
{
irqstate_t flags = px4_enter_critical_section();
hrt_abstime delta = hrt_absolute_time() - *then;
px4_leave_critical_section(flags);
return delta;
}
/**
* Store the absolute time in an interrupt-safe fashion
*/
@@ -719,6 +719,21 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
ts->tv_nsec = abstime * 1000;
}
/**
* Compare a time value with the current time as atomic operation
*/
hrt_abstime
hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
{
irqstate_t flags = px4_enter_critical_section();
hrt_abstime delta = hrt_absolute_time() - *then;
px4_leave_critical_section(flags);
return delta;
}
/**
* Store the absolute time in an interrupt-safe fashion
*/
@@ -318,8 +318,7 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
DMA_SCR_PSIZE_8BITS |
DMA_SCR_MSIZE_8BITS |
DMA_SCR_PBURST_SINGLE |
DMA_SCR_MBURST_SINGLE |
DMA_SCR_TRBUFF);
DMA_SCR_MBURST_SINGLE);
rxdmacfg.cfg2 = 0;
@@ -344,8 +343,7 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
DMA_SCR_PSIZE_8BITS |
DMA_SCR_MSIZE_8BITS |
DMA_SCR_PBURST_SINGLE |
DMA_SCR_MBURST_SINGLE |
DMA_SCR_TRBUFF);
DMA_SCR_MBURST_SINGLE);
txdmacfg.cfg2 = 0;
stm32_dmasetup(_tx_dma, &txdmacfg);
+1
View File
@@ -8,6 +8,7 @@ set(tests
bezier
bitset
bson
conv
dataman
file2
float
@@ -157,6 +157,20 @@ hrt_abstime ts_to_abstime(const struct timespec *ts)
return result;
}
/*
* Compute the delta between a timestamp taken in the past
* and now.
*
* This function is safe to use even if the timestamp is updated
* by an interrupt during execution.
*/
hrt_abstime hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
{
// This is not atomic as the value on the application layer of POSIX is limited.
hrt_abstime delta = hrt_absolute_time() - *then;
return delta;
}
/*
* Store the absolute time in an interrupt-safe fashion.
*
@@ -5,6 +5,7 @@
param load
param set CBRK_SUPPLY_CHK 894281
param set SYS_RESTART_TYPE 0
dataman start
@@ -5,6 +5,7 @@
param load
param set CBRK_SUPPLY_CHK 894281
param set SYS_RESTART_TYPE 0
dataman start
@@ -5,6 +5,7 @@
param load
param set CBRK_SUPPLY_CHK 894281
param set SYS_RESTART_TYPE 0
dataman start
@@ -9,6 +9,7 @@ param set BAT1_N_CELLS 3
param set CBRK_SUPPLY_CHK 894281
param set MAV_TYPE 22
param set VT_TYPE 2
param set SYS_RESTART_TYPE 0
dataman start
+1
View File
@@ -5,6 +5,7 @@
param load
param set CBRK_SUPPLY_CHK 894281
param set SYS_RESTART_TYPE 0
dataman start
+1 -4
View File
@@ -47,9 +47,6 @@ if(NOT "${PX4_BOARD_LABEL}" MATCHES "canbootloader")
set(HW_MINOR ${uavcanblid_hw_version_minor})
set(SW_MAJOR ${uavcanblid_sw_version_major})
set(SW_MINOR ${uavcanblid_sw_version_minor})
if("${uavcanbl_padding}" STREQUAL "")
set(uavcanbl_padding 4)
endif()
math(EXPR HWBOARD_ID "(${HW_MAJOR} << 8) + ${HW_MINOR}")
@@ -71,7 +68,7 @@ if(NOT "${PX4_BOARD_LABEL}" MATCHES "canbootloader")
${PX4_BINARY_DIR}/${uavcan_bl_image_name}
${PX4_BINARY_DIR}/deploy/${HWBOARD_ID}.bin
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/make_can_boot_descriptor.py -v --padding ${uavcanbl_padding} --use-git-hash ${PX4_BOARD}.bin ${uavcan_bl_image_name}
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/make_can_boot_descriptor.py -v --use-git-hash ${PX4_BOARD}.bin ${uavcan_bl_image_name}
COMMAND
COMMAND ${CMAKE_COMMAND} -E make_directory deploy
COMMAND
@@ -120,17 +120,18 @@ class AppDescriptor(object):
class FirmwareImage(object):
def __init__(self, path_or_file, mode="r", padding = 4):
self._padding = padding;
def __init__(self, path_or_file, mode="r"):
if getattr(path_or_file, "read", None):
self._file = path_or_file
self._do_close = False
self._padding = 0
else:
if "b" not in mode:
self._file = open(path_or_file, mode + "b")
else:
self._file = open(path_or_file, mode)
self._do_close = True
self._padding = 4
if "r" in mode:
self._contents = BytesIO(self._file.read())
@@ -215,20 +216,11 @@ class FirmwareImage(object):
prev_offset = self._contents.tell()
self._contents.seek(0, os.SEEK_END)
self._length = self._contents.tell()
# Was Padding requested
if self._padding != 0:
# If so. then is the file already a multiple of the padding?
if 0 == (self._length % self._padding):
# padding not needed
self._padding = 0
# Still need padding
if self._padding:
fill = self._padding - (self._length % self._padding)
if fill:
self._length += fill
#report back the fill which is the padding
self._padding = fill
if self._padding:
fill = self._padding - (self._length % self._padding)
if fill:
self._length += fill
self._padding = fill
self._contents.seek(prev_offset)
return self._length
@@ -293,8 +285,6 @@ if __name__ == "__main__":
metavar="IMAGE")
parser.add_option("-v", "--verbose", dest="verbose", action="store_true",
help="show additional firmware information on stdout")
parser.add_option("-p", "--padding", dest="padding", type= int, default=4,
help="Padds the image to a multple of")
options, args = parser.parse_args()
if len(args) not in (0, 2):
@@ -325,8 +315,8 @@ if __name__ == "__main__":
bootloader_size = int(options.bootloader_size)
with FirmwareImage(in_file, "rb", 0) as in_image:
with FirmwareImage(out_file, "wb", options.padding) as out_image:
with FirmwareImage(in_file, "rb") as in_image:
with FirmwareImage(out_file, "wb") as out_image:
image = in_image.read()
out_image.write(bootloader_image)
out_image.write(image[bootloader_size:])
@@ -271,10 +271,7 @@ CameraTrigger::CameraTrigger() :
param_get(_p_distance, &_distance);
param_get(_p_mode, (int32_t *)&_trigger_mode);
param_get(_p_interface, (int32_t *)&_camera_interface_mode);
if (_p_cam_cap_fback != PARAM_INVALID) {
param_get(_p_cam_cap_fback, (int32_t *)&_cam_cap_fback);
}
param_get(_p_cam_cap_fback, (int32_t *)&_cam_cap_fback);
switch (_camera_interface_mode) {
#ifdef __PX4_NUTTX
@@ -320,6 +317,8 @@ CameraTrigger::CameraTrigger() :
if (!_cam_cap_fback) {
_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger);
} else {
_trigger_pub = orb_advertise(ORB_ID(camera_trigger_secondary), &trigger);
}
}
@@ -844,10 +843,11 @@ CameraTrigger::engage(void *arg)
trigger.feedback = false;
trigger.timestamp = hrt_absolute_time();
// Publish only if _cam_cap_fback is disabled, otherwise, it is published over camera_capture driver
if (!trig->_cam_cap_fback) {
orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trigger);
} else {
orb_publish(ORB_ID(camera_trigger_secondary), trig->_trigger_pub, &trigger);
}
// increment frame count
@@ -72,12 +72,7 @@ SDP3X::init_sdp3x()
int
SDP3X::configure()
{
int ret = write_command(SDP3X_CONT_MODE_STOP);
if (ret == PX4_OK) {
px4_udelay(500); // SDP3X is unresponsive for 500us after stop continuous measurement command
ret = write_command(SDP3X_CONT_MEAS_AVG_MODE);
}
int ret = write_command(SDP3X_CONT_MEAS_AVG_MODE);
if (ret != PX4_OK) {
perf_count(_comms_errors);
@@ -56,7 +56,6 @@
#define SDP3X_RESET_ADDR 0x00
#define SDP3X_RESET_CMD 0x06
#define SDP3X_CONT_MEAS_AVG_MODE 0x3615
#define SDP3X_CONT_MODE_STOP 0x3FF9
#define SDP3X_SCALE_PRESSURE_SDP31 60
#define SDP3X_SCALE_PRESSURE_SDP32 240
+9
View File
@@ -110,6 +110,15 @@ static inline hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
return hrt_absolute_time() - *then;
}
/**
* Compute the delta between a timestamp taken in the past
* and now.
*
* This function is safe to use even if the timestamp is updated
* by an interrupt during execution.
*/
__EXPORT extern hrt_abstime hrt_elapsed_time_atomic(const volatile hrt_abstime *then);
/**
* Store the absolute time in an interrupt-safe fashion.
*
+3
View File
@@ -215,6 +215,9 @@ typedef uint16_t servo_position_t;
/** force safety switch on (to enable use of safety switch) */
#define PWM_SERVO_SET_FORCE_SAFETY_ON _PX4_IOC(_PWM_SERVO_BASE, 28)
/** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */
#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _PX4_IOC(_PWM_SERVO_BASE, 32)
/** set auxillary output mode */
#define PWM_SERVO_ENTER_TEST_MODE 18
#define PWM_SERVO_EXIT_TEST_MODE 19
+80
View File
@@ -0,0 +1,80 @@
/****************************************************************************
*
* Copyright (c) 2012-2014 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 drv_rc_input.h
*
* R/C input interface.
*/
#ifndef _DRV_RC_INPUT_H
#define _DRV_RC_INPUT_H
#include <stdint.h>
#include <sys/ioctl.h>
#include <uORB/topics/input_rc.h>
#include "drv_orb_dev.h"
/**
* Path for the default R/C input device.
*
* Note that on systems with more than one R/C input path (e.g.
* PX4FMU with PX4IO connected) there may be other devices that
* respond to this protocol.
*
* Input data may be obtained by subscribing to the input_rc
* object, or by poll/reading from the device.
*/
#define RC_INPUT0_DEVICE_PATH "/dev/input_rc0"
/**
* Maximum RSSI value
*/
#define RC_INPUT_RSSI_MAX 100
/**
* Input signal type, value is a control position from zero to 100
* percent.
*/
typedef uint16_t rc_input_t;
#define _RC_INPUT_BASE 0x2b00
/** Enable RSSI input via ADC */
#define RC_INPUT_ENABLE_RSSI_ANALOG _IOC(_RC_INPUT_BASE, 1)
/** Enable RSSI input via PWM signal */
#define RC_INPUT_ENABLE_RSSI_PWM _IOC(_RC_INPUT_BASE, 2)
#endif /* _DRV_RC_INPUT_H */
-1
View File
@@ -182,7 +182,6 @@
#define DRV_DIST_DEVTYPE_GY_US42 0x9C
#define DRV_BAT_DEVTYPE_BATMON_SMBUS 0x9d
#define DRV_POWER_DEVTYPE_INA238 0x9E
#define DRV_GPIO_DEVTYPE_MCP23009 0x9F
#define DRV_GPS_DEVTYPE_ASHTECH 0xA0
+1 -10
View File
@@ -242,18 +242,9 @@ int DShot::send_command_thread_safe(const dshot_command_t command, const int num
cmd.num_repetitions = num_repetitions;
_new_command.store(&cmd);
hrt_abstime timestamp_for_timeout = hrt_absolute_time();
// wait until main thread processed it
while (_new_command.load()) {
if (hrt_elapsed_time(&timestamp_for_timeout) < 2_s) {
px4_usleep(1000);
} else {
_new_command.store(nullptr);
PX4_WARN("DShot command timeout!");
}
px4_usleep(1000);
}
return 0;
+36 -16
View File
@@ -51,6 +51,7 @@
#include <drivers/drv_sensor.h>
#include <lib/drivers/device/Device.hpp>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <px4_platform_common/atomic.h>
@@ -204,6 +205,10 @@ private:
px4::atomic<int> _scheduled_reset{(int)GPSRestartType::None};
perf_counter_t _gps_set_clock_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": set clock interval")};
bool _update_system_time{true};
/**
* Publish the gps struct
*/
@@ -259,9 +264,11 @@ private:
*/
void dumpGpsData(uint8_t *data, size_t len, gps_dump_comm_mode_t mode, bool msg_to_gps_device);
void setClock(timespec *rtc_gps_time);
void initializeCommunicationDump();
static constexpr int SET_CLOCK_DRIFT_TIME_S{5}; ///< RTC drift time when time synchronization is needed (in seconds)
static constexpr int SET_CLOCK_DRIFT_TIME_NS{500 * 1000 * 1000}; ///< RTC drift time when time synchronization is needed (in nanoseconds)
};
px4::atomic_bool GPS::_is_gps_main_advertised{false};
@@ -353,14 +360,14 @@ GPS::~GPS()
delete _dump_to_device;
delete _dump_from_device;
delete _helper;
perf_free(_gps_set_clock_perf);
}
int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
{
GPS *gps = (GPS *)user;
timespec rtc_system_time;
switch (type) {
case GPSCallbackType::readDeviceData: {
int timeout;
@@ -391,19 +398,7 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
break;
case GPSCallbackType::setClock:
px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time);
timespec rtc_gps_time = *(timespec *)data1;
int drift_time = abs(rtc_system_time.tv_sec - rtc_gps_time.tv_sec);
if (drift_time >= SET_CLOCK_DRIFT_TIME_S) {
// as of 2021 setting the time on Nuttx temporarily pauses interrupts
// so only set the time if it is very wrong.
// TODO: clock slewing of the RTC for small time differences
px4_clock_settime(CLOCK_REALTIME, &rtc_gps_time);
}
gps->setClock(static_cast<timespec *>(data1));
break;
}
@@ -680,6 +675,29 @@ void GPS::dumpGpsData(uint8_t *data, size_t len, gps_dump_comm_mode_t mode, bool
}
}
void GPS::setClock(timespec *rtc_gps_time)
{
if (_update_system_time) {
px4_clock_settime(CLOCK_REALTIME, rtc_gps_time);
perf_count(_gps_set_clock_perf);
_update_system_time = false;
} else {
timespec rtc_system_time;
px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time);
const int64_t system_time = rtc_system_time.tv_sec * 1e9 + rtc_system_time.tv_nsec;
const int64_t gps_time = rtc_gps_time->tv_sec * 1e9 + rtc_gps_time->tv_nsec;
int64_t drift_time = abs(system_time - gps_time);
if (drift_time > SET_CLOCK_DRIFT_TIME_NS) {
// update clock immediately on next callback
_update_system_time = true;
}
}
}
void
GPS::run()
{
@@ -1036,6 +1054,8 @@ GPS::print_status()
PX4_INFO("sat info: %s", (_p_report_sat_info != nullptr) ? "enabled" : "disabled");
PX4_INFO("rate reading: \t\t%6i B/s", _rate_reading);
perf_print_counter(_gps_set_clock_perf);
if (_report_gps_pos.timestamp != 0) {
if (_helper) {
PX4_INFO("rate position: \t\t%6.2f Hz", (double)_helper->getPositionUpdateRate());
+47 -7
View File
@@ -48,6 +48,9 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/module.h>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
using namespace time_literals;
@@ -75,20 +78,26 @@ public:
void RunImpl();
private:
protected:
void print_status() override;
int send_led_enable(bool enable);
int send_led_rgb();
int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b);
private:
float _brightness{1.0f};
float _max_brightness{1.0f};
uint8_t _r{0};
uint8_t _g{0};
uint8_t _b{0};
bool _leds_enabled{true};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
LedController _led_controller;
int send_led_enable(bool enable);
int send_led_rgb();
int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b);
void update_params();
};
RGBLED::RGBLED(const I2CSPIDriverConfig &config) :
@@ -110,6 +119,8 @@ RGBLED::init()
send_led_enable(false);
send_led_rgb();
update_params();
// kick off work queue
ScheduleNow();
@@ -155,6 +166,19 @@ RGBLED::print_status()
void
RGBLED::RunImpl()
{
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
update_params();
// Immediately update to change brightness
send_led_rgb();
}
LedControlData led_control_data;
if (_led_controller.update(led_control_data) == 1) {
@@ -243,9 +267,9 @@ RGBLED::send_led_rgb()
{
/* To scale from 0..255 -> 0..15 shift right by 4 bits */
const uint8_t msg[6] = {
SUB_ADDR_PWM0, static_cast<uint8_t>((_b >> 4) * _brightness + 0.5f),
SUB_ADDR_PWM1, static_cast<uint8_t>((_g >> 4) * _brightness + 0.5f),
SUB_ADDR_PWM2, static_cast<uint8_t>((_r >> 4) * _brightness + 0.5f)
SUB_ADDR_PWM0, static_cast<uint8_t>((_b >> 4) * _brightness * _max_brightness + 0.5f),
SUB_ADDR_PWM1, static_cast<uint8_t>((_g >> 4) * _brightness * _max_brightness + 0.5f),
SUB_ADDR_PWM2, static_cast<uint8_t>((_r >> 4) * _brightness * _max_brightness + 0.5f)
};
return transfer(msg, sizeof(msg), nullptr, 0);
}
@@ -270,6 +294,22 @@ RGBLED::get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b)
return ret;
}
void
RGBLED::update_params()
{
int32_t maxbrt = 15;
param_get(param_find("LED_RGB_MAXBRT"), &maxbrt);
maxbrt = maxbrt > 15 ? 15 : maxbrt;
maxbrt = maxbrt < 0 ? 0 : maxbrt;
// A minimum of 2 "on" steps is required for breathe effect
if (maxbrt == 1) {
maxbrt = 2;
}
_max_brightness = maxbrt / 15.0f;
}
void
RGBLED::print_usage()
{
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
* Copyright (c) 2015 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
@@ -31,17 +31,25 @@
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <visibility.h>
/*
* Random number generator provided by the operating system. This can be used
* by the crypto_arch if needed, or it can implement an own HW-specific rng
* @file rgbled_params.c
*
* Parameters defined by the RBG led driver
*
* @author Nate Weibley <nate.weibley@prioria.com>
*/
__BEGIN_DECLS
size_t px4_get_secure_random(uint8_t *out,
size_t outlen);
__END_DECLS
#include <px4_platform_common/px4_config.h>
#include <parameters/param.h>
/**
* RGB Led brightness limit
*
* Set to 0 to disable, 1 for minimum brightness up to 15 (max)
*
* @min 0
* @max 15
* @group System
*/
PARAM_DEFINE_INT32(LED_RGB_MAXBRT, 15);
@@ -44,9 +44,12 @@
#include <drivers/device/i2c.h>
#include <lib/led/led.h>
#include <lib/parameters/param.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/module.h>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
using namespace time_literals;
@@ -78,10 +81,12 @@ public:
private:
int send_led_rgb();
void update_params();
int write(uint8_t reg, uint8_t data);
float _brightness{1.0f};
float _max_brightness{1.0f};
uint8_t _r{0};
uint8_t _g{0};
@@ -90,6 +95,8 @@ private:
volatile bool _should_run{true};
bool _leds_enabled{true};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
LedController _led_controller;
uint8_t _red{NCP5623_LED_PWM0};
@@ -147,6 +154,8 @@ RGBLED_NCP5623C::init()
return ret;
}
update_params();
_running = true;
ScheduleNow();
@@ -171,6 +180,19 @@ RGBLED_NCP5623C::probe()
void
RGBLED_NCP5623C::RunImpl()
{
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
update_params();
// Immediately update to change brightness
send_led_rgb();
}
LedControlData led_control_data;
if (_led_controller.update(led_control_data) == 1) {
@@ -225,7 +247,7 @@ int
RGBLED_NCP5623C::send_led_rgb()
{
uint8_t msg[7] = {0x20, 0x70, 0x40, 0x70, 0x60, 0x70, 0x80};
uint8_t brightness = UINT8_MAX;
uint8_t brightness = 0x1f * _max_brightness;
msg[0] = NCP5623_LED_CURRENT | (brightness & 0x1f);
msg[2] = _red | (uint8_t(_r * _brightness) & 0x1f);
@@ -235,6 +257,21 @@ RGBLED_NCP5623C::send_led_rgb()
return transfer(&msg[0], 7, nullptr, 0);
}
void
RGBLED_NCP5623C::update_params()
{
int32_t maxbrt = 31;
param_get(param_find("LED_RGB1_MAXBRT"), &maxbrt);
maxbrt = maxbrt > 31 ? 31 : maxbrt;
maxbrt = maxbrt < 0 ? 0 : maxbrt;
if (maxbrt == 0) {
maxbrt = 1;
}
_max_brightness = maxbrt / 31.0f;
}
void
RGBLED_NCP5623C::print_usage()
{

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