Compare commits

..

1 Commits

Author SHA1 Message Date
David Sidrane 03a32aa2ce PX4 NuttX with Fat wrap fix Backport 2023-11-13 12:39:44 -08:00
585 changed files with 10673 additions and 25261 deletions
+1 -2
View File
@@ -88,6 +88,7 @@ pipeline {
"nxp_fmuk66-e_socketcan",
"nxp_fmuk66-v3_default",
"nxp_fmuk66-v3_socketcan",
"nxp_fmurt1062-v1_default",
"nxp_mr-canhubk3_default",
"nxp_ucans32k146_canbootloader",
"nxp_ucans32k146_default",
@@ -110,8 +111,6 @@ pipeline {
"px4_fmu-v6c_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",
"px4_fmu-v6xrt_bootloader",
"px4_fmu-v6xrt_default",
"px4_io-v2_default",
"raspberrypi_pico_default",
"sky-drones_smartap-airlink_default",
-5
View File
@@ -18,11 +18,6 @@ jobs:
px4_sitl
]
steps:
- name: install Python 3.10
uses: actions/setup-python@v4
with:
python-version: "3.10"
- uses: actions/checkout@v1
with:
token: ${{secrets.ACCESS_TOKEN}}
+1 -1
View File
@@ -57,6 +57,7 @@ jobs:
mro_x21-777,
nxp_fmuk66-e,
nxp_fmuk66-v3,
nxp_fmurt1062-v1,
nxp_mr-canhubk3,
nxp_ucans32k146,
omnibus_f4sd,
@@ -69,7 +70,6 @@ jobs:
px4_fmu-v6c,
px4_fmu-v6u,
px4_fmu-v6x,
px4_fmu-v6xrt,
raspberrypi_pico,
sky-drones_smartap-airlink,
spracing_h7extreme,
-2
View File
@@ -128,6 +128,4 @@ jobs:
run: |
git clone https://github.com/PX4/px4_msgs.git
rm px4_msgs/msg/*.msg
rm px4_msgs/srv/*.srv
cp msg/*.msg px4_msgs/msg/
cp srv/*.srv px4_msgs/srv/
-32
View File
@@ -1,32 +0,0 @@
name: Nuttx Target with extra env config
on:
push:
branches:
- 'main'
pull_request:
branches:
- '*'
jobs:
build:
runs-on: ubuntu-latest
container: px4io/px4-dev-nuttx-focal:2022-08-12
strategy:
matrix:
config: [
px4_fmu-v5,
]
steps:
- uses: actions/checkout@v1
with:
token: ${{secrets.ACCESS_TOKEN}}
- name: make ${{matrix.config}}
env:
PX4_EXTRA_NUTTX_CONFIG: "CONFIG_NSH_LOGIN_PASSWORD=\"test\";CONFIG_NSH_CONSOLE_LOGIN=y"
run: |
echo "PX4_EXTRA_NUTTX_CONFIG: $PX4_EXTRA_NUTTX_CONFIG"
make ${{matrix.config}} nuttx_context
# Check that the config option is set
grep CONFIG_NSH_LOGIN_PASSWORD build/${{matrix.config}}_default/NuttX/nuttx/.config
-15
View File
@@ -81,16 +81,6 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: px4_fmu-v6x_bootloader
px4_fmu-v6xrt_default:
short: px4_fmu-v6xrt
buildType: MinSizeRel
settings:
CONFIG: px4_fmu-v6xrt_default
px4_fmu-v6xrt_bootloader:
short: px4_fmu-v6xrt_bootloader
buildType: MinSizeRel
settings:
CONFIG: px4_fmu-v6xrt_bootloader
airmind_mindpx-v2_default:
short: airmind_mindpx-v2
buildType: MinSizeRel
@@ -191,11 +181,6 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: cubepilot_cubeorange_test
cubepilot_cubeorangeplus_test:
short: cubepilot_cubeorangeplus
buildType: MinSizeRel
settings:
CONFIG: cubepilot_cubeorangeplus_test
emlid_navio2_default:
short: emlid_navio2
buildType: MinSizeRel
Vendored
-3
View File
@@ -105,7 +105,6 @@ pipeline {
./emsdk activate latest;
cd ..;
. ./_emscripten_sdk/emsdk_env.sh;
git fetch --all --tags;
make failsafe_web;
cd build/px4_sitl_default_failsafe_web;
mkdir -p failsafe_sim;
@@ -231,9 +230,7 @@ pipeline {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git")
// 'main' branch
sh('rm -f px4_msgs/msg/*.msg')
sh('rm -f px4_msgs/srv/*.srv')
sh('cp msg/*.msg px4_msgs/msg/')
sh('cp srv/*.srv px4_msgs/srv/')
sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true')
sh('cd px4_msgs; git push origin main || true')
sh('rm -rf px4_msgs')
+1
View File
@@ -266,6 +266,7 @@ px4fmu_firmware: \
misc_qgc_extra_firmware: \
check_nxp_fmuk66-v3_default \
check_nxp_fmurt1062-v1_default \
check_mro_x21_default \
check_bitcraze_crazyflie_default \
check_bitcraze_crazyflie21_default \
@@ -76,7 +76,6 @@ param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default NPFG_PERIOD 12
param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
@@ -52,8 +52,12 @@ param set-default MAV_1_MODE 9
# param set-default SER_TEL1_BAUD 921600 Not found
# Vehicle attitude PID tuning
param set-default MC_ACRO_EXPO 0
param set-default MC_ACRO_EXPO_Y 0
param set-default MC_ACRO_P_MAX 200
param set-default MC_ACRO_R_MAX 200
param set-default MC_ACRO_SUPEXPO 0
param set-default MC_ACRO_SUPEXPOY 0
param set-default MC_ACRO_Y_MAX 150
param set-default MC_PITCHRATE_D 0.0015
param set-default MC_ROLLRATE_D 0.0015
@@ -92,7 +92,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
fi
# start gz_bridge
if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
if [ -n "${PX4_GZ_MODEL}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
# model specified, gz_bridge will spawn model
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
@@ -106,7 +106,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
fi
# start gz bridge with pose arg.
if gz_bridge start -p "${model_pose}" -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if gz_bridge start -p "${model_pose}" -m "${PX4_GZ_MODEL}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
@@ -129,7 +129,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
exit 1
fi
elif [ -n "${PX4_GZ_MODEL_NAME}" ]; then
elif [ -n "${PX4_GZ_MODEL_NAME}" ] && [ -z "${PX4_GZ_MODEL}" ]; then
# model name specificed, gz_bridge will attach to existing model
if gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
@@ -155,8 +155,35 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
exit 1
fi
elif [ -n "${PX4_SIM_MODEL}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ] && [ -z "${PX4_GZ_MODEL}" ]; then
echo "WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL."
if gz_bridge start -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if param compare -s SENS_EN_BAROSIM 1
then
sensor_baro_sim start
fi
if param compare -s SENS_EN_GPSSIM 1
then
sensor_gps_sim start
fi
if param compare -s SENS_EN_MAGSIM 1
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
fi
else
echo "ERROR [init] gz_bridge failed to start"
exit 1
fi
else
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_SIM_MODEL"
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_GZ_MODEL"
exit 1
fi
@@ -45,8 +45,12 @@ param set-default MAV_1_MODE 9
param set-default SER_TEL1_BAUD 921600
# Vehicle attitude PID tuning
param set-default MC_ACRO_EXPO 0
param set-default MC_ACRO_EXPO_Y 0
param set-default MC_ACRO_P_MAX 200
param set-default MC_ACRO_R_MAX 200
param set-default MC_ACRO_SUPEXPO 0
param set-default MC_ACRO_SUPEXPOY 0
param set-default MC_ACRO_Y_MAX 150
param set-default MC_PITCHRATE_D 0.0015
param set-default MC_ROLLRATE_D 0.0015
@@ -45,8 +45,12 @@ param set-default MAV_1_MODE 9
param set-default SER_TEL1_BAUD 921600
# Vehicle attitude PID tuning
param set-default MC_ACRO_EXPO 0
param set-default MC_ACRO_EXPO_Y 0
param set-default MC_ACRO_P_MAX 200
param set-default MC_ACRO_R_MAX 200
param set-default MC_ACRO_SUPEXPO 0
param set-default MC_ACRO_SUPEXPOY 0
param set-default MC_ACRO_Y_MAX 150
param set-default MC_PITCHRATE_D 0.0015
param set-default MC_ROLLRATE_D 0.0015
@@ -0,0 +1,65 @@
#!/bin/sh
#
# @name Reaper 500 Quad
#
# @type Quadrotor H
# @class Copter
#
# @maintainer Blankered
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_ROLLRATE_P 0.14
param set-default MC_ROLLRATE_I 0.1
param set-default MC_ROLLRATE_D 0.004
param set-default MC_PITCH_P 6
param set-default MC_PITCHRATE_P 0.14
param set-default MC_PITCHRATE_I 0.09
param set-default MC_PITCHRATE_D 0.004
param set-default MC_YAW_P 4
param set-default NAV_ACC_RAD 2
param set-default RTL_RETURN_ALT 30
param set-default RTL_DESCEND_ALT 10
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15
param set-default CA_ROTOR0_KM -0.05
param set-default CA_ROTOR1_PX -0.15
param set-default CA_ROTOR1_PY -0.15
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR2_PX 0.15
param set-default CA_ROTOR2_PY -0.15
param set-default CA_ROTOR2_KM 0.05
param set-default CA_ROTOR3_PX -0.15
param set-default CA_ROTOR3_PY 0.15
param set-default CA_ROTOR3_KM 0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_MIN1 1100
param set-default PWM_MAIN_MIN2 1100
param set-default PWM_MAIN_MIN3 1100
param set-default PWM_MAIN_MIN4 1100
param set-default PWM_MAIN_MAX1 1900
param set-default PWM_MAIN_MAX2 1900
param set-default PWM_MAIN_MAX3 1900
param set-default PWM_MAIN_MAX4 1900
param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_TIM1 50
param set-default PWM_MAIN_TIM2 50
param set-default PWM_AUX_TIM0 50
param set-default PWM_AUX_TIM1 50
param set-default PWM_AUX_TIM2 50
@@ -0,0 +1,91 @@
#!/bin/sh
#
# @name Crazyflie 2
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Dennis Shtatov <densht@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v3 exclude
# @board px4_fmu-v4 exclude
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board diatone_mamba-f405-mk2 exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 1
param set-default BAT1_CAPACITY 240
param set-default BAT1_SOURCE 1
param set-default CBRK_SUPPLY_CHK 894281
param set-default COM_RC_IN_MODE 1
param set-default EKF2_ABL_LIM 2
param set-default EKF2_HGT_REF 2
param set-default EKF2_RNG_CTRL 2
param set-default EKF2_MAG_TYPE 1
param set-default EKF2_OF_CTRL 1
param set-default EKF2_OF_DELAY 10
param set-default IMU_GYRO_CUTOFF 100
param set-default IMU_ACCEL_CUTOFF 30
param set-default MC_AIRMODE 1
param set-default IMU_DGYRO_CUTOFF 70
param set-default MC_PITCHRATE_D 0.002
param set-default MC_PITCHRATE_P 0.07
param set-default MC_ROLLRATE_D 0.002
param set-default MC_ROLLRATE_P 0.07
param set-default MC_YAW_P 3
param set-default MPC_THR_HOVER 0.7
param set-default MPC_Z_P 1.5
param set-default MPC_Z_VEL_P_ACC 8
param set-default MPC_Z_VEL_I_ACC 6
param set-default MPC_HOLD_MAX_XY 0.1
param set-default MPC_MAX_FLOW_HGT 3
param set-default NAV_RCL_ACT 3
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.03
param set-default CA_ROTOR0_PY 0.03
param set-default CA_ROTOR1_PX -0.03
param set-default CA_ROTOR1_PY 0.03
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR2_PX -0.03
param set-default CA_ROTOR2_PY -0.03
param set-default CA_ROTOR3_PX 0.03
param set-default CA_ROTOR3_PY -0.03
param set-default CA_ROTOR3_KM -0.05
# Run the motors at 328.125 kHz (recommended)
param set-default PWM_MAIN_TIM0 3921
param set-default PWM_MAIN_TIM1 3921
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_DIS0 0
param set-default PWM_MAIN_DIS1 0
param set-default PWM_MAIN_DIS2 0
param set-default PWM_MAIN_DIS3 0
param set-default PWM_MAIN_MIN0 0
param set-default PWM_MAIN_MIN1 0
param set-default PWM_MAIN_MIN2 0
param set-default PWM_MAIN_MIN3 0
param set-default PWM_MAIN_MAX0 255
param set-default PWM_MAIN_MAX1 255
param set-default PWM_MAIN_MAX2 255
param set-default PWM_MAIN_MAX3 255
param set-default SENS_FLOW_MINRNG 0.05
syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
@@ -13,8 +13,6 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT1_N_CELLS 4
param set-default EKF2_GBIAS_INIT 0.01
@@ -54,9 +52,10 @@ param set-default GND_MAX_ANG 3.1415
# Set geometry & output configration
param set-default CA_AIRFRAME 6
param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_DIS1 1500
param set-default PWM_MAIN_DIS2 1500
param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_TIM1 50
param set-default RBCLW_ADDRESS 128
param set-default RBCLW_FUNC1 101
param set-default RBCLW_FUNC2 102
param set-default RBCLW_REV 1
@@ -58,6 +58,7 @@ px4_add_romfs_files(
4017_nxp_hovergames
4019_x500_v2
4020_holybro_px4vision_v1_5
4040_reaper
4041_beta75x
4050_generic_250
4052_holybro_qav250
@@ -66,6 +67,7 @@ px4_add_romfs_files(
4071_ifo
4073_ifo-s
4500_clover4
4900_crazyflie
4901_crazyflie21
# [5000, 5999] Quadrotor +"
+1 -1
View File
@@ -17,7 +17,7 @@ param set-default COM_POS_FS_DELAY 5
# there is a 2.5 factor applied on the _FS thresholds if for invalidation
param set-default COM_POS_FS_EPH 50
param set-default COM_VEL_FS_EVH 3
param set-default COM_VEL_FS_EVH 5
param set-default COM_POS_LOW_EPH 50
+22 -24
View File
@@ -170,7 +170,7 @@ else
param select-backup $PARAM_BACKUP_FILE
fi
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X PX4_FMU_V6XRT
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X
then
netman update -i eth0
fi
@@ -274,39 +274,37 @@ else
. $FCONFIG
fi
if px4io supported
then
# Check if PX4IO present and update firmware if needed.
if [ -f $IOFW ]
if [ -f $IOFW ]
then
if ! px4io checkcrc ${IOFW}
then
if ! px4io checkcrc ${IOFW}
then
# tune Program PX4IO
tune_control play -t 16 # tune 16 = PROG_PX4IO
# tune Program PX4IO
tune_control play -t 16 # tune 16 = PROG_PX4IO
if px4io update ${IOFW}
if px4io update ${IOFW}
then
usleep 10000
tune_control stop
if px4io checkcrc ${IOFW}
then
usleep 10000
tune_control stop
if px4io checkcrc ${IOFW}
then
tune_control play -t 17 # tune 17 = PROG_PX4IO_OK
else
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
fi
tune_control play -t 17 # tune 17 = PROG_PX4IO_OK
else
tune_control stop
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
fi
fi
if ! px4io start
then
echo "PX4IO start failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
else
tune_control stop
fi
fi
if ! px4io start
then
echo "PX4IO start failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
fi
fi
#
# RC update (map raw RC input to calibrate manual control)
# start before commander
+10 -15
View File
@@ -43,11 +43,6 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find estimator_states instance', multi_instance)
try:
estimator_sensor_bias = ulog.get_dataset('estimator_sensor_bias', multi_instance).data
except:
raise PreconditionError('could not find estimator_sensor_bias instance', multi_instance)
try:
estimator_innovations = ulog.get_dataset('estimator_innovations', multi_instance).data
estimator_innovation_variances = ulog.get_dataset('estimator_innovation_variances', multi_instance).data
@@ -304,21 +299,21 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.save()
data_plot.close()
# Plot the gyro bias estimates
# Plot the delta angle bias estimates
data_plot = CheckFlagsPlot(
1e-6 * estimator_sensor_bias['timestamp'], estimator_sensor_bias,
[['gyro_bias[0]'], ['gyro_bias[1]'], ['gyro_bias[2]']],
x_label='time (sec)', y_labels=['X (rad/s)', 'Y (rad/s)', 'Z (rad/s)'],
plot_title='Gyro Bias Estimates', annotate=False, pdf_handle=pdf_pages)
1e-6 * estimator_states['timestamp'], estimator_states,
[['states[10]'], ['states[11]'], ['states[12]']],
x_label='time (sec)', y_labels=['X (rad)', 'Y (rad)', 'Z (rad)'],
plot_title='Delta Angle Bias Estimates', annotate=False, pdf_handle=pdf_pages)
data_plot.save()
data_plot.close()
# Plot the accel bias estimates
# Plot the delta velocity bias estimates
data_plot = CheckFlagsPlot(
1e-6 * estimator_sensor_bias['timestamp'], estimator_sensor_bias,
[['accel_bias[0]'], ['accel_bias[1]'], ['accel_bias[2]']],
x_label='time (sec)', y_labels=['X (m/s^2)', 'Y (m/s^2)', 'Z (m/s^2)'],
plot_title='Accel Bias Estimates', annotate=False, pdf_handle=pdf_pages)
1e-6 * estimator_states['timestamp'], estimator_states,
[['states[13]'], ['states[14]'], ['states[15]']],
x_label='time (sec)', y_labels=['X (m/s)', 'Y (m/s)', 'Z (m/s)'],
plot_title='Delta Velocity Bias Estimates', annotate=False, pdf_handle=pdf_pages)
data_plot.save()
data_plot.close()
+7 -1
View File
@@ -302,6 +302,12 @@ When set to -1 (default), the value depends on the function (see {:}).
for key, label, param_suffix, description in standard_params_array:
if key in standard_params:
# values must be in range of an uint16_t
if standard_params[key]['min'] < 0:
raise Exception('minimum value for {:} expected >= 0 (got {:})'.format(key, standard_params[key]['min']))
if standard_params[key]['max'] >= 1<<16:
raise Exception('maximum value for {:} expected <= {:} (got {:})'.format(key, 1<<16, standard_params[key]['max']))
if key == 'failsafe':
standard_params[key]['default'] = -1
standard_params[key]['min'] = -1
@@ -311,7 +317,7 @@ When set to -1 (default), the value depends on the function (see {:}).
'short': channel_label+' ${i} '+label+' Value',
'long': description
},
'type': 'float',
'type': 'int32',
'instance_start': instance_start,
'instance_start_label': instance_start_label,
'num_instances': num_channels,
@@ -146,7 +146,6 @@ def write_fields_to_hpp_file(file_name: str, definitions: dict, window_length: i
format_list: [str]):
max_tokenized_field_length, max_tokenized_field_length_msg = max(
((len(definitions[k]['fields']), k) for k in definitions), key=itemgetter(0))
max_untokenized_field_length = max(definitions[k]['fields_total_length'] for k in definitions)
max_num_orb_ids = max(len(definitions[k]['orb_ids']) for k in definitions)
max_num_orb_id_dependencies = max(len(definitions[k]['dependencies']) for k in definitions)
@@ -168,7 +167,6 @@ const uint8_t* orb_compressed_message_formats();
unsigned orb_compressed_message_formats_size();
static constexpr unsigned orb_tokenized_fields_max_length = {MAX_TOKENIZED_FIELD_LENGTH}; // {MAX_TOKENIZED_FIELD_LENGTH_MSG}
static constexpr unsigned orb_untokenized_fields_max_length = {MAX_UNTOKENIZED_FIELD_LENGTH};
static constexpr unsigned orb_compressed_max_num_orb_ids = {MAX_NUM_ORB_IDS};
static constexpr unsigned orb_compressed_max_num_orb_id_dependencies = {MAX_NUM_ORB_ID_DEPENDENCIES};
@@ -181,7 +179,6 @@ static constexpr unsigned orb_compressed_heatshrink_lookahead_length = {LOOKAHEA
'''
.replace('{MAX_TOKENIZED_FIELD_LENGTH}', str(max_tokenized_field_length))
.replace('{MAX_TOKENIZED_FIELD_LENGTH_MSG}', max_tokenized_field_length_msg)
.replace('{MAX_UNTOKENIZED_FIELD_LENGTH}', str(max_untokenized_field_length))
.replace('{MAX_NUM_ORB_IDS}', str(max_num_orb_ids))
.replace('{MAX_NUM_ORB_ID_DEPENDENCIES}', str(max_num_orb_id_dependencies))
.replace('{WINDOW_LENGTH}', str(window_length))
@@ -171,61 +171,6 @@ def get_children_fields(base_type, search_path):
return spec_temp.parsed_fields()
def get_message_fields_str_for_message_hash(msg_fields, search_path):
"""
Get all fields (including for nested types) in the form of:
'''
uint64 timestamp
uint8 esc_count
uint8 esc_online_flags
EscReport[8] esc
uint64 timestamp
uint32 esc_errorcount
int32 esc_rpm
float32 esc_voltage
uint16 failures
int8 esc_power
'''
"""
all_fields_str = ''
for field in msg_fields:
if field.is_header:
continue
type_name = field.type
# detect embedded types
sl_pos = type_name.find('/')
if sl_pos >= 0:
type_name = type_name[sl_pos + 1:]
all_fields_str += type_name + ' ' + field.name + '\n'
if sl_pos >= 0: # nested type, add all nested fields
children_fields = get_children_fields(field.base_type, search_path)
all_fields_str += get_message_fields_str_for_message_hash(children_fields, search_path)
return all_fields_str
def hash_32_fnv1a(data: str):
hash_val = 0x811c9dc5
prime = 0x1000193
for i in range(len(data)):
value = ord(data[i])
hash_val = hash_val ^ value
hash_val *= prime
hash_val &= 0xffffffff
return hash_val
def get_message_hash(msg_fields, search_path):
"""
Get a 32 bit message hash over all fields
"""
all_fields_str = get_message_fields_str_for_message_hash(msg_fields, search_path)
return hash_32_fnv1a(all_fields_str)
def add_padding_bytes(fields, search_path):
"""
Add padding fields before the embedded types, at the end and calculate the
+2 -2
View File
@@ -124,7 +124,7 @@ static inline constexpr int ucdr_topic_size_@(topic)()
return @(struct_size);
}
static inline bool ucdr_serialize_@(topic)(const void* data, ucdrBuffer& buf, int64_t time_offset = 0)
bool ucdr_serialize_@(topic)(const void* data, ucdrBuffer& buf, int64_t time_offset = 0)
{
const @(uorb_struct)& topic = *static_cast<const @(uorb_struct)*>(data);
@{
@@ -153,7 +153,7 @@ for field_type, field_name, field_size, padding in fields:
return true;
}
static inline bool ucdr_deserialize_@(topic)(ucdrBuffer& buf, @(uorb_struct)& topic, int64_t time_offset = 0)
bool ucdr_deserialize_@(topic)(ucdrBuffer& buf, @(uorb_struct)& topic, int64_t time_offset = 0)
{
@{
for field_type, field_name, field_size, padding in fields:
+1 -2
View File
@@ -58,7 +58,6 @@ from px_generate_uorb_topic_helper import * # this is in Tools/
uorb_struct = '%s_s'%name_snake_case
message_hash = get_message_hash(spec.parsed_fields(), search_path)
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
}@
@@ -75,7 +74,7 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
@[for topic in topics]@
static_assert(static_cast<orb_id_size_t>(ORB_ID::@topic) == @(all_topics.index(topic)), "ORB_ID index mismatch");
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic));
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), static_cast<orb_id_size_t>(ORB_ID::@topic));
@[end for]
void print_message(const orb_metadata *meta, const @uorb_struct& message)
-1
View File
@@ -42,7 +42,6 @@ for field in spec.parsed_fields():
{
@# join all msg files in one line e.g: "float[3] position;float[3] velocity;bool armed;"
"fields": @( json.dumps(bytearray(";".join(topic_fields)+";", 'utf-8').decode('unicode_escape')) ),
"fields_total_length": @(sum([len(convert_type(field.type))+1+len(field.name)+1 for field in sorted_fields])),
"orb_ids": @( json.dumps([ all_topics.index(topic) for topic in topics]) ),
"main_orb_id": @( all_topics.index(name_snake_case) if name_snake_case in all_topics else -1 ),
"dependencies": @( json.dumps(list(set(dependencies))) ),
-16
View File
@@ -250,22 +250,6 @@ class SourceParser(object):
event.group = "arming_check"
event.prepend_arguments([('navigation_mode_group_t', 'modes'),
('uint8_t', 'health_component_index')])
elif call in ['reporter.healthFailureExt', 'reporter.armingCheckFailureExt']: # from ROS2
assert len(args_split) == num_args + 3, \
"Unexpected Number of arguments for: {:}, {:}".format(args_split, num_args)
m = self.re_event_id.search(args_split[0])
if m:
_, event_name = m.group(1, 2)
else:
raise Exception("Could not extract event ID from {:}".format(args_split[0]))
event.name = event_name
event.message = args_split[2][1:-1]
if 'health' in call:
event.group = "health"
else:
event.group = "arming_check"
event.prepend_arguments([('navigation_mode_group_t', 'modes'),
('uint8_t', 'health_component_index')])
else:
raise Exception("unknown event method call: {}, args: {}".format(call, args))
+38 -10
View File
@@ -1,7 +1,7 @@
#! /usr/bin/env bash
## Bash script to setup PX4 development environment on Arch Linux.
## Tested on Arch 2023-03-01
## Tested on Manjaro 20.2.1.
##
## Installs:
## - Common dependencies and tools for nuttx, jMAVSim
@@ -50,7 +50,6 @@ sudo pacman -Sy --noconfirm --needed \
cmake \
cppcheck \
doxygen \
fuse2 \
gdb \
git \
gnutls \
@@ -67,7 +66,7 @@ sudo pacman -Sy --noconfirm --needed \
# Python dependencies
echo "Installing PX4 Python3 dependencies"
pip install --break-system-packages -r ${DIR}/${REQUIREMENTS_FILE}
pip install --user -r ${DIR}/requirements.txt
# NuttX toolchain (arm-none-eabi-gcc)
if [[ $INSTALL_NUTTX == "true" ]]; then
@@ -75,17 +74,45 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
echo "Installing NuttX dependencies"
sudo pacman -S --noconfirm --needed \
arm-none-eabi-gcc \
arm-none-eabi-newlib \
gperf \
vim \
;
if [ ! -z "$USER" ]; then
# add user to dialout group (serial port access)
sudo echo usermod -aG uucp $USER
sudo usermod -aG uucp $USER
fi
# don't run modem manager (interferes with PX4 serial port usage)
sudo systemctl disable --now ModemManager
# remove modem manager (interferes with PX4 serial port usage)
sudo pacman -R modemmanager --noconfirm
# arm-none-eabi-gcc
NUTTX_GCC_VERSION="10-2020-q4-major"
NUTTX_GCC_VERSION_SHORT="10-2020q4"
source $HOME/.profile # load changed path for the case the script is reran before relogin
if [ $(which arm-none-eabi-gcc) ]; then
GCC_VER_STR=$(arm-none-eabi-gcc --version)
GCC_FOUND_VER=$(echo $GCC_VER_STR | grep -c "${NUTTX_GCC_VERSION}")
fi
if [[ "$GCC_FOUND_VER" == "1" ]]; then
echo "arm-none-eabi-gcc-${NUTTX_GCC_VERSION} found, skipping installation"
else
echo "Installing arm-none-eabi-gcc-${NUTTX_GCC_VERSION}";
wget -O /tmp/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-linux.tar.bz2 https://armkeil.blob.core.windows.net/developer/Files/downloads/gnu-rm/${NUTTX_GCC_VERSION_SHORT}/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-x86_64-linux.tar.bz2 && \
sudo tar -jxf /tmp/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-linux.tar.bz2 -C /opt/;
# add arm-none-eabi-gcc to user's PATH
exportline="export PATH=/opt/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}/bin:\$PATH"
if grep -Fxq "$exportline" $HOME/.profile; then
echo "${NUTTX_GCC_VERSION} path already set.";
else
echo $exportline >> $HOME/.profile;
fi
fi
fi
# Simulation tools
@@ -95,7 +122,8 @@ if [[ $INSTALL_SIM == "true" ]]; then
# java (jmavsim)
sudo pacman -S --noconfirm --needed \
ant
ant \
jdk-openjdk \
;
# Gazebo setup
@@ -133,5 +161,5 @@ fi
if [[ $INSTALL_NUTTX == "true" ]]; then
echo
echo "Reboot or logout, login computer before attempting to flash NuttX targets"
echo "Reboot or logout, login computer before attempting to build NuttX targets"
fi
+1 -1
View File
@@ -2,7 +2,7 @@ argcomplete
argparse>=1.2
cerberus
coverage
empy==3.3.4
empy>=3.3
future
jinja2>=2.8
jsonschema
+1 -1
View File
@@ -155,7 +155,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
if [ -n "$USER" ]; then
# add user to dialout group (serial port access)
sudo usermod -aG dialout $USER
sudo usermod -a -G dialout $USER
fi
# arm-none-eabi-gcc
@@ -4,7 +4,6 @@
#------------------------------------------------------------------------------
param set-default IMU_GYRO_RATEMAX 1000
param set-default SENS_IMU_CLPNOTI 0
# Internal SPI
if ! paw3902 -s start -Y 180
@@ -5,7 +5,6 @@
param set-default CBRK_IO_SAFETY 0
param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0
safety_button start
tone_alarm start
@@ -7,7 +7,6 @@ param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0
safety_button start
tone_alarm start
@@ -3,8 +3,6 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default SENS_IMU_CLPNOTI 0
pwm_out start
dshot start
+3 -3
View File
@@ -30,7 +30,7 @@ then
if [ $HAVE_PM3 = yes ]
then
ina226 -X -b 3 -t 3 -k start
ina226 -X -b 3 -t 2 -k start
fi
fi
@@ -46,7 +46,7 @@ then
if [ $HAVE_PM3 = yes ]
then
ina228 -X -b 3 -t 3 -k start
ina228 -X -b 3 -t 2 -k start
fi
fi
@@ -62,7 +62,7 @@ then
if [ $HAVE_PM3 = yes ]
then
ina238 -X -b 3 -t 3 -k start
ina238 -X -b 3 -t 2 -k start
fi
fi
+1 -1
View File
@@ -14,7 +14,7 @@ CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
@@ -8,7 +8,7 @@ board_adc start
# but there might also be an MPU6000
if ! mpu6000 -R 6 -s start
then
icm42688p -R 6 -s start
icm20689 -R 6 -s start
fi
bmp280 -X start
+1 -1
View File
@@ -14,7 +14,7 @@ CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
@@ -4,9 +4,6 @@
#------------------------------------------------------------------------------
board_adc start
if ! bmi270 -s -q start
then
icm42688p -R 0 -s start
fi
bmi270 -R 6 -s start
bmp280 -X start
+1 -1
View File
@@ -14,7 +14,7 @@ CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
@@ -4,9 +4,6 @@
#------------------------------------------------------------------------------
board_adc start
if ! bmi270 -s -q start
then
icm42688p -R 0 -s start
fi
bmi270 -s start
bmp280 -X start
+1 -1
View File
@@ -15,9 +15,9 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_NXP_FXAS21002C=y
CONFIG_DRIVERS_IMU_NXP_FXOS8701CQ=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_LIGHTS_RGBLED=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
@@ -1,36 +1,28 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_LINKER_PREFIX="ocram"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI055=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_COMMON_UWB=y
CONFIG_DRIVERS_UWB_UWB_SR150=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -45,7 +37,6 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -57,27 +48,21 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_IO_BYPASS_CONTROL=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NETMAN=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
@@ -1,10 +1,10 @@
{
"board_id": 35,
"board_id": 31,
"magic": "PX4FWv1",
"description": "Firmware for the PX4FMUv6XRT board",
"description": "Firmware for the NXPFMURT1062v1 board",
"image": "",
"build_time": 0,
"summary": "PX4FMUv6XRT",
"summary": "NXPFMURT1062v1",
"version": "0.1",
"image_size": 0,
"image_maxsize": 7340032,
@@ -0,0 +1,10 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1097
param set-default BAT1_A_PER_V 15.391030303
rgbled_pwm start
safety_button start
@@ -0,0 +1,34 @@
#!/bin/sh
#
# PX4 FMUv5 specific board sensors init
#------------------------------------------------------------------------------
#
# UART mapping on NXP FMURT1062:
#
# LPUART7 /dev/ttyS0 CONSOLE
# LPUART2 /dev/ttyS1 GPS
# LPUART3 /dev/ttyS2 TELEM2 (GPIO flow control)
# LPUART4 /dev/ttyS3 TELEM1 (UART flow control)
# LPUART5 /dev/ttyS4 TELEM4 GPS2
# LPUART6 /dev/ttyS5 TELEM3 (RC_INPUT)
# LPUART8 /dev/ttyS6 PX4IO
#
#------------------------------------------------------------------------------
board_adc start
# Internal SPI bus ICM-20602
icm20602 -R 2 -s start
# Internal SPI bus ICM-20689
icm20689 -R 2 -s start
# Internal SPI bus BMI055 accel/gyro
bmi055 -A -R 2 -s start
bmi055 -G -R 2 -s start
# internal compass
ist8310 -I -R 10 start
# Baro on internal SPI
ms5611 -s start
@@ -5,12 +5,12 @@
choice
prompt "Boot Flash"
default PX4_FMU_V6XRT_V3_QSPI_FLASH
default NXP_FMURT1062_V3_QSPI_FLASH
config PX4_FMU_V6XRT_V3_HYPER_FLASH
config NXP_FMURT1062_V3_HYPER_FLASH
bool "HYPER Flash"
config PX4_FMU_V6XRT_V3_QSPI_FLASH
config NXP_FMURT1062_V3_QSPI_FLASH
bool "QSPI Flash"
endchoice # Boot Flash
@@ -39,21 +39,3 @@ config BOARD_FORCE_ALIGNMENT
Adds -mno-unaligned-access to build flags. to force alignment.
This can be needed if data is stored in a region of memory, that
is Strongly ordered and dcache is off.
config BOARD_BOOTLOADER_INVALID_FCB
bool "Disables the FCB header"
default n
---help---
This can be used to keep the ROM bootloader in the serial Download mode.
Thus preventing bootlooping on `is_debug_pending` in the lame Rev B
silicon ROM bootloader. You can not cold boot (Power cycle) but can
Jtag from Load and be abel to reset it.
config BOARD_BOOTLOADER_FIXUP
bool "Restores OCTAL Flash when No FCB"
default n
select ARCH_RAMFUNCS
---help---
Restores OCTAL Flash when FCB is invalid.
@@ -0,0 +1,400 @@
/************************************************************************************
* nuttx-configs/nxp_fmurt1062-v1/include/board.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* Set VDD_SOC to 1.3V */
#define IMXRT_VDD_SOC (0x14)
/* Set Arm PLL (PLL1) to fOut = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR
* 576Mhz = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR
* ARM_PLL_DIV_SELECT = 96
* ARM_PODF_DIVISOR = 2
* 576Mhz = (24Mhz * 96/2) / 2
*
* AHB_CLOCK_ROOT = PLL1fOut / IMXRT_AHB_PODF_DIVIDER
* 1Hz to 600 Mhz = 576Mhz / IMXRT_ARM_CLOCK_DIVIDER
* IMXRT_ARM_CLOCK_DIVIDER = 1
* 576Mhz = 576Mhz / 1
*
* PRE_PERIPH_CLK_SEL = PRE_PERIPH_CLK_SEL_PLL1
* PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF, 1 select PRE_PERIPH_CLK_SEL_PLL1)
* PERIPH_CLK = 576Mhz
*
* IPG_CLOCK_ROOT = AHB_CLOCK_ROOT / IMXRT_IPG_PODF_DIVIDER
* IMXRT_IPG_PODF_DIVIDER = 4
* 144Mhz = 576Mhz / 4
*
* PRECLK_CLOCK_ROOT = IPG_CLOCK_ROOT / IMXRT_PERCLK_PODF_DIVIDER
* IMXRT_PERCLK_PODF_DIVIDER = 1
* 16Mhz = 144Mhz / 9
*
* SEMC_CLK_ROOT = 576Mhz / IMXRT_SEMC_PODF_DIVIDER (labeled AIX_PODF in 18.2)
* IMXRT_SEMC_PODF_DIVIDER = 8
* 72Mhz = 576Mhz / 8
*
* Set Sys PLL (PLL2) to fOut = (24Mhz * (20+(2*(DIV_SELECT)))
* 528Mhz = (24Mhz * (20+(2*(1)))
*
* Set USB1 PLL (PLL3) to fOut = (24Mhz * 20)
* 480Mhz = (24Mhz * 20)
*
* Set LPSPI PLL3 PFD0 to fOut = (480Mhz / 12 * 18)
* 720Mhz = (480Mhz / 12 * 18)
* 90Mhz = (720Mhz / LSPI_PODF_DIVIDER)
*
* Set LPI2C PLL3 / 8 to fOut = (480Mhz / 8)
* 60Mhz = (480Mhz / 8)
* 12Mhz = (60Mhz / LSPI_PODF_DIVIDER)
*
* Set USDHC1 PLL2 PFD2 to fOut = (528Mhz / 24 * 18)
* 396Mhz = (528Mhz / 24 * 18)
* 198Mhz = (396Mhz / IMXRT_USDHC1_PODF_DIVIDER)
*/
#define BOARD_XTAL_FREQUENCY 24000000
#define IMXRT_PRE_PERIPH_CLK_SEL CCM_CBCMR_PRE_PERIPH_CLK_SEL_PLL1
#define IMXRT_PERIPH_CLK_SEL CCM_CBCDR_PERIPH_CLK_SEL_PRE_PERIPH
#define IMXRT_ARM_PLL_DIV_SELECT 96
#define IMXRT_ARM_PODF_DIVIDER 2
#define IMXRT_AHB_PODF_DIVIDER 1
#define IMXRT_IPG_PODF_DIVIDER 4
#define IMXRT_PERCLK_CLK_SEL CCM_CSCMR1_PERCLK_CLK_SEL_IPG_CLK_ROOT
#define IMXRT_PERCLK_PODF_DIVIDER 9
#define IMXRT_SEMC_PODF_DIVIDER 8
#define IMXRT_LPSPI_CLK_SELECT CCM_CBCMR_LPSPI_CLK_SEL_PLL3_PFD0
#define IMXRT_LSPI_PODF_DIVIDER 8
#define IMXRT_LPI2C_CLK_SELECT CCM_CSCDR2_LPI2C_CLK_SEL_PLL3_60M
#define IMXRT_LSI2C_PODF_DIVIDER 5
#define IMXRT_USDHC1_CLK_SELECT CCM_CSCMR1_USDHC1_CLK_SEL_PLL2_PFD0
#define IMXRT_USDHC1_PODF_DIVIDER 2
#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20
#define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22
#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20
#define BOARD_CPU_FREQUENCY \
(BOARD_XTAL_FREQUENCY * (IMXRT_ARM_PLL_DIV_SELECT / 2)) / IMXRT_ARM_PODF_DIVIDER
#define BOARD_GPT_FREQUENCY \
(BOARD_CPU_FREQUENCY / IMXRT_IPG_PODF_DIVIDER) / IMXRT_PERCLK_PODF_DIVIDER
/* Define this to enable tracing */
#if CONFIG_USE_TRACE
# define IMXRT_TRACE_PODF_DIVIDER 1
# define IMXRT_TRACE_CLK_SELECT CCM_CBCMR_TRACE_CLK_SEL_PLL2_PFD0
#endif
/* SDIO *****************************************************************************/
/* Pin drive characteristics */
#define USDHC1_DATAX_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
#define USDHC1_CMD_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
#define USDHC1_CLK_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_SPEED_MAX)
#define USDHC1_CD_IOMUX (IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_02 */
#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_03 */
#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_04 */
#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_05 */
#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | USDHC1_CLK_IOMUX) /* GPIO_SD_B0_01 */
#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | USDHC1_CMD_IOMUX) /* GPIO_SD_B0_00 */
#define PIN_USDHC1_CD (GPIO_USDHC1_CD_2 | USDHC1_CD_IOMUX) /* GPIO_B1_12 */
/* Ideal 400Khz for initial inquiry.
* Given input clock 198 Mhz.
* 386.71875 KHz = 198 Mhz / (256 * 2)
*/
#define BOARD_USDHC_IDMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV256
#define BOARD_USDHC_IDMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(2)
/* Ideal 25 Mhz for other modes
* Given input clock 198 Mhz.
* 24.75 MHz = 198 Mhz / (8 * 1)
*/
#define BOARD_USDHC_MMCMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_MMCMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD1MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD1MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD4MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD4MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
/* LED definitions ******************************************************************/
/* The nxp fmutr1062 board has numerous LEDs but only three, LED_GREEN a Green LED,
* LED_BLUE a Blue LED and LED_RED a Red LED, that can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* PIO Disambiguation ***************************************************************/
/* LPUARTs
*/
#define LPUART_IOMUX (IOMUX_PULL_UP_22K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW | IOMUX_SPEED_LOW | IOMUX_SCHMITT_TRIGGER)
/* GPS 1 */
#define GPIO_LPUART2_RX (GPIO_LPUART2_RX_1 | LPUART_IOMUX) /* EVK J22-8 */ /* GPIO_AD_B1_03 */
#define GPIO_LPUART2_TX (GPIO_LPUART2_TX_1 | LPUART_IOMUX) /* EVK J22-7 */ /* GPIO_AD_B1_02 */
/* N.B. Rev B schematic did not change the names of the nets. Just the silk screen renamed the ports
* Such that Telem 2 had the real HW HS signals. The imx driver to dated does not support GOIO controlled
* HS lines
*/
/* Telem 1 */
#define HS_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_SLEW_SLOW | IOMUX_DRIVE_HIZ | IOMUX_SPEED_MEDIUM | IOMUX_PULL_UP_47K)
#define HS_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_PULL_KEEP)
#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_3 | LPUART_IOMUX) /* GPIO_B0_09 */
#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_3 | LPUART_IOMUX) /* GPIO_B0_08 */
#define GPIO_LPUART3_CTS (GPIO_PORT3 | GPIO_PIN4 | GPIO_INPUT | HS_INPUT_IOMUX) /* GPIO_SD_B1_04 GPIO3_IO04 (GPIO only, no HW Flow control) */
#define GPIO_LPUART3_RTS (GPIO_PORT4 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | HS_OUTPUT_IOMUX) /* GPIO_EMC_24 GPIO4_IO24 (GPIO only, no HW Flow control) */
/* Telem 2 */
#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_2 | LPUART_IOMUX) /* GPIO_EMC_20 */
#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_2 | LPUART_IOMUX) /* GPIO_EMC_19 */
#define GPIO_LPUART4_CTS (GPIO_LPUART4_CTS_1 | LPUART_IOMUX) /* GPIO_EMC_17 */
#define GPIO_LPUART4_RTS (GPIO_LPUART4_RTS_1 | LPUART_IOMUX) /* GPIO_EMC_18 */
/* GPS2 */
#define GPIO_LPUART5_RX (GPIO_LPUART5_RX_1 | LPUART_IOMUX) /* GPIO_B1_13 */
#define GPIO_LPUART5_TX (GPIO_LPUART5_TX_2 | LPUART_IOMUX) /* GPIO_EMC_23 */
/* RC INPUT single wire mode on TX, RX is not used */
#define GPIO_LPUART6_RX (GPIO_LPUART6_RX_2 | LPUART_IOMUX) /* GPIO_EMC_26 */
#define GPIO_LPUART6_TX (GPIO_LPUART6_TX_2 | LPUART_IOMUX) /* GPIO_EMC_25 */
#define GPIO_LPUART7_RX (GPIO_LPUART7_RX_1 | LPUART_IOMUX) /* GPIO_EMC_32 */
#define GPIO_LPUART7_TX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */
#define GPIO_LPUART8_RX (GPIO_LPUART8_RX_2 | LPUART_IOMUX) /* GPIO_EMC_39 */
#define GPIO_LPUART8_TX (GPIO_LPUART8_TX_2 | LPUART_IOMUX) /* GPIO_EMC_38 */
/* CAN
*
* CAN1 is routed to transceiver.
* CAN2 is routed to transceiver.
* CAN3 is routed to transceiver.
*/
#define FLEXCAN_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MEDIUM)
#define GPIO_FLEXCAN1_RX (GPIO_FLEXCAN1_RX_2 | FLEXCAN_IOMUX) /* GPIO_B0_03 */
#define GPIO_FLEXCAN1_TX (GPIO_FLEXCAN1_TX_4 | FLEXCAN_IOMUX) /* GPIO_SD_B1_02 */
#define GPIO_FLEXCAN2_RX (GPIO_FLEXCAN2_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_03 */
#define GPIO_FLEXCAN2_TX (GPIO_FLEXCAN2_TX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_02 */
#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_11 */
#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_36 */
/* LPSPI */
#define LPSPI_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MAX)
#define GPIO_LPSPI1_SCK (GPIO_LPSPI1_SCK_1 | LPSPI_IOMUX) /* GPIO_EMC_27 */
#define GPIO_LPSPI1_MISO (GPIO_LPSPI1_SDI_1 | LPSPI_IOMUX) /* GPIO_EMC_29 */
#define GPIO_LPSPI1_MOSI (GPIO_LPSPI1_SDO_1 | LPSPI_IOMUX) /* GPIO_EMC_28 */
#define GPIO_LPSPI2_SCK (GPIO_LPSPI2_SCK_1 | LPSPI_IOMUX) /* GPIO_EMC_00 */
#define GPIO_LPSPI2_MISO (GPIO_LPSPI2_SDI_1 | LPSPI_IOMUX) /* GPIO_EMC_03 */
#define GPIO_LPSPI2_MOSI (GPIO_LPSPI2_SDO_1 | LPSPI_IOMUX) /* GPIO_EMC_02 */
#define GPIO_LPSPI3_SCK (GPIO_LPSPI3_SCK_1 | LPSPI_IOMUX) /* GPIO_AD_B1_15 */
#define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_1 | LPSPI_IOMUX) /* GPIO_AD_B1_13 */
#define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_1 | LPSPI_IOMUX) /* GPIO_AD_B1_14 */
#define GPIO_LPSPI4_SCK (GPIO_LPSPI4_SCK_1 | LPSPI_IOMUX) /* GPIO_B1_07 */
#define GPIO_LPSPI4_MISO (GPIO_LPSPI4_SDI_1 | LPSPI_IOMUX) /* GPIO_B1_05 */
#define GPIO_LPSPI4_MOSI (GPIO_LPSPI4_SDO_2 | LPSPI_IOMUX) /* GPIO_B0_02 */
/* LPI2Cs */
#define LPI2C_IOMUX (IOMUX_SPEED_MEDIUM | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | GPIO_SION_ENABLE)
#define LPI2C_IO_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | IOMUX_PULL_NONE)
#define GPIO_LPI2C1_SDA (GPIO_LPI2C1_SDA_2 | LPI2C_IOMUX) /* EVK J24-9 R276 */ /* GPIO_AD_B1_01 */
#define GPIO_LPI2C1_SCL (GPIO_LPI2C1_SCL_2 | LPI2C_IOMUX) /* EVK J24-10 R277 */ /* GPIO_AD_B1_00 */
#define GPIO_LPI2C1_SDA_RESET (GPIO_PORT1 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_01 GPIO1_IO17 */
#define GPIO_LPI2C1_SCL_RESET (GPIO_PORT1 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_00 GPIO1_IO16 */
#define GPIO_LPI2C2_SDA (GPIO_LPI2C2_SDA_1 | LPI2C_IOMUX) /* EVK J8-A25 */ /* GPIO_B0_05 */
#define GPIO_LPI2C2_SCL (GPIO_LPI2C2_SCL_1 | LPI2C_IOMUX) /* EVK J8-A24 */ /* GPIO_B0_04 */
#define GPIO_LPI2C2_SDA_RESET (GPIO_PORT2 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_B0_05 GPIO2_IO5 */
#define GPIO_LPI2C2_SCL_RESET (GPIO_PORT2 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_B0_04 GPIO2_IO4 */
#define GPIO_LPI2C3_SDA (GPIO_LPI2C3_SDA_2 | LPI2C_IOMUX) /* GPIO_EMC_21 */
#define GPIO_LPI2C3_SCL (GPIO_LPI2C3_SCL_2 | LPI2C_IOMUX) /* GPIO_EMC_22 */
#define GPIO_LPI2C3_SDA_RESET (GPIO_PORT4 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_21 GPIO4_IO21 */
#define GPIO_LPI2C3_SCL_RESET (GPIO_PORT4 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_22 GPIO4_IO22 */
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
#include <imxrt_gpio.h>
#include <imxrt_iomuxc.h>
// add -I<full path> build/nxp_fmurt1062-v1_default/NuttX/nuttx/arch/arm/src/chip \ to NuttX Makedefs.in
#define PROBE_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE)
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 /* GPIO_B0_06 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_2 /* GPIO_EMC_08 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_3 /* GPIO_EMC_10 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_4 /* GPIO_AD_B0_09 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_5 /* GPIO_EMC_33 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_6 /* GPIO_EMC_30 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_7 /* GPIO_EMC_04 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_8 /* GPIO_EMC_01 */ (GPIO_PORT4 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { imxrt_config_gpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { imxrt_config_gpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { imxrt_config_gpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { imxrt_config_gpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { imxrt_config_gpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { imxrt_config_gpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { imxrt_config_gpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { imxrt_config_gpio(PROBE_8); } \
} while(0)
# define PROBE(n,s) do {imxrt_gpio_write(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H */
@@ -5,24 +5,21 @@
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_NDEBUG is not set
# CONFIG_NSH_DISABLE_MB is not set
# CONFIG_NSH_DISABLE_MH is not set
# CONFIG_NSH_DISABLE_MW is not set
# CONFIG_SPI_CALLBACK is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/px4/fmu-v6xrt/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/fmurt1062-v1/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="imxrt"
CONFIG_ARCH_CHIP_IMXRT=y
CONFIG_ARCH_CHIP_MIMXRT1176DVMAA=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_RAMVECTORS=y
CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y
CONFIG_ARCH_INTERRUPTSTACK=750
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_ITCM=y
@@ -31,39 +28,37 @@ CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_BOOTLOADER_FIXUP=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_CUSTOM_LEDS=y
CONFIG_BOARD_FORCE_ALIGNMENT=y
CONFIG_BOARD_LOOPSPERMSEC=104926
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BOOT_RUNFROMISRAM=y
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_PRODUCTID=0x001d
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v6XRT.x"
CONFIG_CDCACM_PRODUCTSTR="PX4 FMURT1062 v1.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3643
CONFIG_CDCACM_VENDORSTR="Dronecode Project, Inc."
CONFIG_CDCACM_VENDORID=0x1FC9
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_SIZE=70
CONFIG_ETH0_PHY_LAN8742A=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FSUTILS_IPCFG=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
@@ -72,19 +67,9 @@ CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_IMXRT_DTCM=0
CONFIG_IMXRT_EDMA=y
CONFIG_IMXRT_EDMA_EDBG=y
CONFIG_IMXRT_EDMA_ELINK=y
CONFIG_IMXRT_EDMA_NTCD=64
CONFIG_IMXRT_ENET2=y
CONFIG_IMXRT_ENET=y
CONFIG_IMXRT_FLEXCAN1=y
CONFIG_IMXRT_FLEXCAN2=y
CONFIG_IMXRT_FLEXCAN3=y
CONFIG_IMXRT_FLEXSPI2=y
CONFIG_IMXRT_GPIO13_IRQ=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IMXRT_BOOTLOADER_HEAP=y
CONFIG_IMXRT_DTCM_HEAP=y
CONFIG_IMXRT_GPIO1_0_15_IRQ=y
CONFIG_IMXRT_GPIO1_16_31_IRQ=y
CONFIG_IMXRT_GPIO2_0_15_IRQ=y
@@ -97,136 +82,96 @@ CONFIG_IMXRT_GPIO5_0_15_IRQ=y
CONFIG_IMXRT_GPIO5_16_31_IRQ=y
CONFIG_IMXRT_GPIO6_0_15_IRQ=y
CONFIG_IMXRT_GPIO6_16_31_IRQ=y
CONFIG_IMXRT_GPIO7_0_15_IRQ=y
CONFIG_IMXRT_GPIO7_16_31_IRQ=y
CONFIG_IMXRT_GPIO8_0_15_IRQ=y
CONFIG_IMXRT_GPIO8_16_31_IRQ=y
CONFIG_IMXRT_GPIO9_0_15_IRQ=y
CONFIG_IMXRT_GPIO9_16_31_IRQ=y
CONFIG_IMXRT_GPIO_IRQ=y
CONFIG_IMXRT_INIT_FLEXRAM=y
CONFIG_IMXRT_ITCM=0
CONFIG_IMXRT_LPI2C1=y
CONFIG_IMXRT_LPI2C2=y
CONFIG_IMXRT_LPI2C3=y
CONFIG_IMXRT_LPI2C6=y
CONFIG_IMXRT_LPI2C_DMA=y
CONFIG_IMXRT_LPI2C_DMA_MAXMSG=16
CONFIG_IMXRT_LPI2C_DYNTIMEO=y
CONFIG_IMXRT_LPI2C_DYNTIMEO_STARTSTOP=10
CONFIG_IMXRT_LPSPI1=y
CONFIG_IMXRT_LPSPI1_DMA=y
CONFIG_IMXRT_LPSPI2=y
CONFIG_IMXRT_LPSPI2_DMA=y
CONFIG_IMXRT_LPSPI3=y
CONFIG_IMXRT_LPSPI3_DMA=y
CONFIG_IMXRT_LPSPI6=y
CONFIG_IMXRT_LPSPI_DMA=y
CONFIG_IMXRT_LPUART10=y
CONFIG_IMXRT_LPUART11=y
CONFIG_IMXRT_LPUART1=y
CONFIG_IMXRT_LPSPI4=y
CONFIG_IMXRT_LPUART2=y
CONFIG_IMXRT_LPUART3=y
CONFIG_IMXRT_LPUART4=y
CONFIG_IMXRT_LPUART5=y
CONFIG_IMXRT_LPUART6=y
CONFIG_IMXRT_LPUART7=y
CONFIG_IMXRT_LPUART8=y
CONFIG_IMXRT_LPUART_INVERT=y
CONFIG_IMXRT_LPUART_SINGLEWIRE=y
CONFIG_IMXRT_PHY_POLLING=y
CONFIG_IMXRT_PHY_PROVIDES_TXC=y
CONFIG_IMXRT_RTC_MAGIC_REG=1
CONFIG_IMXRT_SNVS_LPSRTC=y
CONFIG_IMXRT_USBDEV=y
CONFIG_IMXRT_USDHC1=y
CONFIG_IMXRT_USDHC1_INVERT_CD=y
CONFIG_IMXRT_USDHC1_WIDTH_D1_D4=y
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=2944
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_THROTTLE=0
CONFIG_IPCFG_BINARY=y
CONFIG_IPCFG_CHARDEV=y
CONFIG_IPCFG_PATH="/fs/mtd_net"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_LPI2C1_DMA=y
CONFIG_LPI2C2_DMA=y
CONFIG_LPI2C3_DMA=y
CONFIG_LPUART10_IFLOWCONTROL=y
CONFIG_LPUART10_OFLOWCONTROL=y
CONFIG_LPUART10_RXBUFSIZE=600
CONFIG_LPUART10_RXDMA=y
CONFIG_LPUART10_TXBUFSIZE=3000
CONFIG_LPUART10_TXDMA=y
CONFIG_LPUART1_BAUD=57600
CONFIG_LPUART1_SERIAL_CONSOLE=y
CONFIG_LPUART2_BAUD=57600
CONFIG_LPUART2_RXBUFSIZE=600
CONFIG_LPUART2_TXBUFSIZE=1500
CONFIG_LPUART3_BAUD=57600
CONFIG_LPUART3_IFLOWCONTROL=y
CONFIG_LPUART3_OFLOWCONTROL=y
CONFIG_LPUART3_RXBUFSIZE=600
CONFIG_LPUART3_RXDMA=y
CONFIG_LPUART3_TXBUFSIZE=3000
CONFIG_LPUART3_TXDMA=y
CONFIG_LPUART4_BAUD=57600
CONFIG_LPUART4_IFLOWCONTROL=y
CONFIG_LPUART4_OFLOWCONTROL=y
CONFIG_LPUART4_RXBUFSIZE=600
CONFIG_LPUART4_RXDMA=y
CONFIG_LPUART4_TXBUFSIZE=3000
CONFIG_LPUART4_TXDMA=y
CONFIG_LPUART4_TXBUFSIZE=1500
CONFIG_LPUART5_BAUD=57600
CONFIG_LPUART5_RXBUFSIZE=600
CONFIG_LPUART5_RXDMA=y
CONFIG_LPUART5_TXBUFSIZE=1500
CONFIG_LPUART5_TXDMA=y
CONFIG_LPUART6_BAUD=57600
CONFIG_LPUART6_RXBUFSIZE=600
CONFIG_LPUART6_RXDMA=y
CONFIG_LPUART6_TXBUFSIZE=1500
CONFIG_LPUART6_TXDMA=y
CONFIG_LPUART7_BAUD=57600
CONFIG_LPUART7_RXBUFSIZE=120
CONFIG_LPUART7_SERIAL_CONSOLE=y
CONFIG_LPUART7_TXBUFSIZE=1500
CONFIG_LPUART8_BAUD=57600
CONFIG_LPUART8_IFLOWCONTROL=y
CONFIG_LPUART8_OFLOWCONTROL=y
CONFIG_LPUART8_RXDMA=y
CONFIG_LPUART8_TXBUFSIZE=10000
CONFIG_LPUART8_TXDMA=y
CONFIG_LPUART8_RXBUFSIZE=600
CONFIG_LPUART8_TXBUFSIZE=1500
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=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_NET=y
CONFIG_NETDB_DNSCLIENT=y
CONFIG_NETDB_DNSSERVER_NOADDR=y
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
CONFIG_NETDEV_LATEINIT=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETINIT_DHCPC=y
CONFIG_NETINIT_DNS=y
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
CONFIG_NETINIT_MONITOR=y
CONFIG_NETINIT_THREAD=y
CONFIG_NETINIT_THREAD_PRIORITY=49
CONFIG_NETUTILS_TELNETD=y
CONFIG_NET_ARP_IPIN=y
CONFIG_NET_ARP_SEND=y
CONFIG_NET_BROADCAST=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_EXTID=y
CONFIG_NET_CAN_NOTIFIER=y
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_ETH_PKTSIZE=1518
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_SOCKET=y
CONFIG_NET_SOLINGER=y
CONFIG_NET_TCP=y
CONFIG_NET_TCPBACKLOG=y
CONFIG_NET_TCP_DELAYED_ACK=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NET_UDP=y
CONFIG_NET_UDP_CHECKSUMS=y
CONFIG_NET_UDP_WRITE_BUFFERS=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_BASENAME=y
CONFIG_NSH_DISABLE_CMP=y
CONFIG_NSH_DISABLE_DD=y
CONFIG_NSH_DISABLE_DIRNAME=y
CONFIG_NSH_DISABLE_HEXDUMP=y
CONFIG_NSH_DISABLE_LOSETUP=y
CONFIG_NSH_DISABLE_MKFIFO=y
CONFIG_NSH_DISABLE_MKRD=y
CONFIG_NSH_DISABLE_PRINTF=y
CONFIG_NSH_DISABLE_PUT=y
CONFIG_NSH_DISABLE_REBOOT=y
CONFIG_NSH_DISABLE_UNAME=y
CONFIG_NSH_DISABLE_WGET=y
CONFIG_NSH_DISABLE_XD=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -234,15 +179,16 @@ CONFIG_NSH_READLINE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_TELNET_LOGIN=y
CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=1835008
CONFIG_RAM_START=0x20240000
CONFIG_RAM_SIZE=1048576
CONFIG_RAM_START=0x20200000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
@@ -271,10 +217,7 @@ CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_CLE=y
CONFIG_SYSTEM_DHCPC_RENEW=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_PING=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
@@ -0,0 +1,299 @@
/****************************************************************************
* boards/arm/imxrt/imxrt1060-evk/scripts/flash-ocram.ld
*
* Copyright (C) 2018, 2020 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david.sidrane@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The FMURT1062 has 8MiB of QSPI FLASH beginning at address,
* 0x0060:0000, Up to 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM
* beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this
* configuration.
*
* The default flexram setting on the iMXRT 1062 is
* 256Kib to OCRRAM, 128Kib ITCM and 128Kib DTCM.
* This can be changed by using a dcd by minipulating
* IOMUX GPR16 and GPR17.
* The configuration we will use is 384Kib to OCRRAM, 0Kib ITCM and
* 128Kib DTCM.
*
* This is the OCRAM inker script.
* The NXP ROM bootloader will move the FLASH image to OCRAM.
* We must reserve 32K for the bootloader' OCRAM usage from the OCRAM Size
* and an additinal 8K for the ivt_s which is IVT_SIZE(8K) This 40K can be
* reused once the application is running.
*
* 0x2020:A000 to 0x202d:ffff - The application Image's vector table
* 0x2020:8000 to 0x2020:A000 - IVT
* 0x2020:0000 to 0x2020:7fff - NXP ROM bootloader.
*
* We artificially split the FLASH to allow locating sections that we do not
* want loaded inoto OCRAM. This is to save on OCRAM where the speen of the
* code does not matter.
*
*/
MEMORY
{
flash (rx) : ORIGIN = 0x60000000, LENGTH = 7M
flashxip (rx) : ORIGIN = 0x60700000, LENGTH = 1M
/* Vectors @ boot+ivt OCRAM2 Flex RAM Boot IVT */
sram (rwx) : ORIGIN = 0x2020A000, LENGTH = 512K + 256K + 128K - (32K + 8K)
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 0K
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
EXTERN(g_flash_config)
EXTERN(g_image_vector_table)
EXTERN(g_boot_data)
EXTERN(g_dcd_data)
ENTRY(_stext)
SECTIONS
{
/* Image Vector Table and Boot Data for booting from external flash */
.boot_hdr : ALIGN(4)
{
FILL(0xff)
__boot_hdr_start__ = ABSOLUTE(.) ;
KEEP(*(.boot_hdr.conf))
. = 0x1000 ;
KEEP(*(.boot_hdr.ivt))
. = 0x1020 ;
KEEP(*(.boot_hdr.boot_data))
. = 0x1030 ;
KEEP(*(.boot_hdr.dcd_data))
__boot_hdr_end__ = ABSOLUTE(.) ;
. = 0x2000 ;
} > flash
/* Catch all the section we want not in OCRAM so that the *(.text .text.*) in flash does not */
/* Sift and sort with arm-none-eabi-nm -C -S -n build/nxp_fmurt1062-v1_default/nxp_fmurt1062-v1_default.elf > list.txt */
.flashxip : ALIGN(4)
{
FILL(0xff)
/* Order matters */
*(.text.__start)
*(.text.imxrt_ocram_initialize)
*(.slow_memory)
*(.text.romfs*)
*(.text.cromfs*)
*(.text.mpu*)
*(.text.arm_memfault*)
*(.text.arm_hardfault*)
*(.text.up_assert*)
*(.text.up_stackdump*)
*(.text.up_taskdump*)
*(.text.up_mdelay*)
*(.text.up_udelay*)
*(.text.board_on_reset*)
*(.text.board_spi_reset*)
*(.text.board_query_manifest*)
*(.text.board_reset*)
*(.text.board_get*)
*(.text.board_mcu*)
*(.text.imxrt_xbar_connect*)
*(.text.bson*)
*(.text.*print_load*)
*(.text.*px4_mft*)
*(.text.*px4_mtd*)
*(.text.syslog*)
*(.text.register_driver*)
*(.text.nx_start*)
*(.text.nx_bringup*)
*(.text.irq_unexpected_isr*)
*(.text.group*)
*(.text.*setenv*)
*(.text.*env*)
*(.text.cmd*)
*(.text.readline*)
*(.text.mkfatfs*)
*(.text.builtin*)
*(.text.basename*)
*(.text.dirname*)
*(.text.gmtime_r*)
*(.text.chdir*)
*(.text.devnull*)
*(.text.ramdisk*)
*(.text.files*)
*(.text.unregister_driver*)
*(.text.register_blockdriver*)
*(.text.bchdev_register*)
*(.text.part*)
*(.text.ftl*)
*(.text.*I2CBusIterator*)
*(.text.*SPIBusIterator*)
*(.text.*BusCLIArguments*)
*(.text.*WorkQueueManager*)
*(.text.*param_export*)
*(.text.*param_import*)
*(.text.*param_load*)
*(.text.*BusInstanceIterator*)
*(.text.*PRINT_MODULE_USAGE*)
*(.text.*px4_getopt*)
*(.text.*main*)
*(.text.*instantiate*)
*(.text.*ADC*)
*(.text.*MS5611*)
*(.text.*I2CSPIDriver*)
*(.text.*CameraCapture*)
*(.text.*i2cdetect*)
*(.text.*usage*)
/* *(.text.*Bosch*) 2% CPU .5% RAM */
*(.text.*Tunes*)
*(.text.*printStatistics*)
*(.text.*init*)
*(.text.*test*)
*(.text.*task_spawn*)
*(.text.*custom_command*)
*(.text.*print_usage*)
*(.text.*print_status*)
*(.text.*status*)
*(.text.*CameraInterface*)
*(.text.*CameraTrigger*)
*(.text.*ModuleBase*)
*(.text.*print_message*)
*(.text._ZN4Ekf2C2Eb)
*(.text._ZN9CommanderC2Ev)
*(.text.*PreFlightCheck*)
*(.text.*calibrat*)
*(.text.*initEv)
*(.text.*probe*)
*(.text.*thread_main*);
*(.text.*listener*)
*(.text.*BlockLocalPositionEstimator*)
*(.text.nsh_*)
*(.text.lib_vscanf)
*(.text.lib_vsprintf)
*(.text.*configure_streams_to_default*)
*(.text.*_main)
*(.text.*GPSDriverAshtech*)
*(.text.*GPSDriver*)
*(.text.*Mavlink*)
*(.rodata .rodata.*)
*(.fixup)
*(.gnu.warning)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
} > flashxip
/* Sections that will go to OCRAM */
.text :
{
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
_etext = ABSOLUTE(.);
} > sram AT> flash
/*
* Init functions (static constructors and the like)
*/
.init_section :
{
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab :
{
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx :
{
*(.ARM.exidx*)
__exidx_end = ABSOLUTE(.);
} > flash
_eronly = ABSOLUTE(.);
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.ramfunc ALIGN(4):
{
_sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > flash
_framfuncs = LOADADDR(.ramfunc);
.bss :
{
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -0,0 +1,163 @@
/****************************************************************************
* configs/nxp_fmurt1062-v1/scripts/flash.ld
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The FMURT1062 has 8MiB of QSPI FLASH beginning at address,
* 0x0060:0000, Up to 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM
* beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this
* configuratin.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x60000000, LENGTH = 8M
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 768K
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 128K
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
EXTERN(g_flash_config)
EXTERN(g_image_vector_table)
EXTERN(g_boot_data)
ENTRY(_stext)
SECTIONS
{
/* Image Vector Table and Boot Data for booting from external flash */
.boot_hdr : ALIGN(4)
{
FILL(0xff)
__boot_hdr_start__ = ABSOLUTE(.) ;
KEEP(*(.boot_hdr.conf))
. = 0x1000 ;
KEEP(*(.boot_hdr.ivt))
. = 0x1020 ;
KEEP(*(.boot_hdr.boot_data))
. = 0x1030 ;
KEEP(*(.boot_hdr.dcd_data))
__boot_hdr_end__ = ABSOLUTE(.) ;
. = 0x2000 ;
} >flash
.text :
{
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section :
{
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab :
{
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx :
{
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.ramfunc ALIGN(4):
{
_sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > flash
_framfuncs = LOADADDR(.ramfunc);
.bss :
{
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2023 PX4 Development Team. All rights reserved.
# Copyright (c) 2016, 2019 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,13 +31,27 @@
#
############################################################################
px4_add_library(arch_bootloader
main.c
systick.c
px4_add_library(drivers_board
autoleds.c
automount.c
can.c
i2c.cpp
init.c
led.c
sdhc.c
spi.cpp
timer_config.cpp
usb.c
manifest.c
imxrt_flexspi_nor_boot.c
imxrt_flexspi_nor_flash.c
)
target_link_libraries(arch_bootloader
target_link_libraries(drivers_board
PRIVATE
bootloader_lib
nuttx_arch
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)
@@ -46,21 +46,21 @@
* BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8
*
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
* the PX4 fmu-v6xrt. The following definitions describe how NuttX controls
* the NXP fmurt1062-v1. The following definitions describe how NuttX controls
* the LEDs:
*
* SYMBOL Meaning LED state
* RED GREEN BLUE
* ------------------- ----------------------- -----------------
* LED_STARTED NuttX has been started OFF OFF OFF
* LED_HEAPALLOCATE Heap has been allocated OFF OFF ON
* LED_IRQSENABLED Interrupts enabled OFF OFF ON
* LED_STACKCREATED Idle stack created OFF ON OFF
* LED_INIRQ In an interrupt (no change)
* LED_SIGNAL In a signal handler (no change)
* LED_ASSERTION An assertion failed (no change)
* LED_PANIC The system has crashed FLASH OFF OFF
* LED_IDLE fmu-v6xrt is in sleep mode (Optional, not used)
* SYMBOL Meaning LED state
* RED GREEN BLUE
* ------------------- ----------------------- -----------------
* LED_STARTED NuttX has been started OFF OFF OFF
* LED_HEAPALLOCATE Heap has been allocated OFF OFF ON
* LED_IRQSENABLED Interrupts enabled OFF OFF ON
* LED_STACKCREATED Idle stack created OFF ON OFF
* LED_INIRQ In an interrupt (no change)
* LED_SIGNAL In a signal handler (no change)
* LED_ASSERTION An assertion failed (no change)
* LED_PANIC The system has crashed FLASH OFF OFF
* LED_IDLE K66 is in sleep mode (Optional, not used)
*/
/****************************************************************************
+502
View File
@@ -0,0 +1,502 @@
/****************************************************************************
*
* Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* NXP fmukrt1062-v1 internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include "imxrt_gpio.h"
#include "imxrt_iomuxc.h"
#include "hardware/imxrt_pinmux.h"
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* PX4IO connection configuration */
#if 0 // There is no PX4IO Support on first out
// This requires serial DMA driver
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS6"
#define PX4IO_SERIAL_TX_GPIO GPIO_LPUART8_TX_2
#define PX4IO_SERIAL_RX_GPIO GPIO_LPUART8_RX_2
#define PX4IO_SERIAL_BASE IMXRT_LPUART8_BASE
#define PX4IO_SERIAL_VECTOR IMXRT_IRQ_LPUART8
#define PX4IO_SERIAL_TX_DMAMAP
#define PX4IO_SERIAL_RX_DMAMAP
#define PX4IO_SERIAL_RCC_REG
#define PX4IO_SERIAL_RCC_EN
#define PX4IO_SERIAL_CLOCK
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
#endif
/* Configuration ************************************************************************************/
/* FMURT1062 GPIOs ***********************************************************************************/
/* LEDs */
/* An RGB LED is connected through GPIO as shown below:
*/
#define LED_IOMUX (IOMUX_OPENDRAIN | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW)
#define GPIO_nLED_RED /* GPIO_B0_00 QTIMER1_TIMER0 GPIO2_IO0 */ (GPIO_PORT2 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_GREEN /* GPIO_B0_01 QTIMER1_TIMER1 GPIO2_IO1 */ (GPIO_PORT2 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_BLUE /* GPIO_B1_08 QTIMER1_TIMER3 GPIO2_IO24 */ (GPIO_PORT2 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_BLUE
/*
* Define the ability to shut off off the sensor signals
* by changing the signals to inputs
*/
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT))
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */
#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST)
#define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
/* SPI1 off */
#define _GPIO_LPSPI1_SCK /* GPIO_EMC_27 GPIO4_IO27 */ (GPIO_PORT4 | GPIO_PIN27 | CS_IOMUX)
#define _GPIO_LPSPI1_MISO /* GPIO_EMC_29 GPIO4_IO29 */ (GPIO_PORT4 | GPIO_PIN29 | CS_IOMUX)
#define _GPIO_LPSPI1_MOSI /* GPIO_EMC_28 GPIO4_IO28 */ (GPIO_PORT4 | GPIO_PIN28 | CS_IOMUX)
#define GPIO_SPI1_SCK_OFF _PIN_OFF(_GPIO_LPSPI1_SCK)
#define GPIO_SPI1_MISO_OFF _PIN_OFF(_GPIO_LPSPI1_MISO)
#define GPIO_SPI1_MOSI_OFF _PIN_OFF(_GPIO_LPSPI1_MOSI)
#define _GPIO_LPSPI3_SCK /* GPIO_AD_B1_15 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN31 | CS_IOMUX)
#define _GPIO_LPSPI3_MISO /* GPIO_AD_B1_13 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN29 | CS_IOMUX)
#define _GPIO_LPSPI3_MOSI /* GPIO_AD_B1_14 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN30 | CS_IOMUX)
#define GPIO_SPI3_SCK_OFF _PIN_OFF(_GPIO_LPSPI3_SCK)
#define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO)
#define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI)
/* Define the SPI4 Data Ready and Control signals */
#define GPIO_SPI4_DRDY7_EXTERNAL1 /* GPIO_EMC_35 GPIO3_IO21*/ (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_nSPI4_RESET_EXTERNAL1 /* GPIO_B1_00 GPIO2_IO16 */ (GPIO_PORT2 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_SPI4_SYNC_EXTERNAL1 /* GPIO_EMC_05 GPIO4_IO5 */(GPIO_PORT4 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_DRDY_OFF_SPI4_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI4_DRDY7_EXTERNAL1)
#define GPIO_nSPI4_RESET_EXTERNAL1_OFF _PIN_OFF(GPIO_nSPI4_RESET_EXTERNAL1)
#define GPIO_SPI4_SYNC_EXTERNAL1_OFF _PIN_OFF(GPIO_SPI4_SYNC_EXTERNAL1)
#define ADC_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ)
#define ADC1_CH(n) (n)
#define ADC1_GPIO(n, p) (GPIO_PORT1 | GPIO_PIN##p | ADC_IOMUX) //
/* Define GPIO pins used as ADC N.B. Channel numbers are for reference, */
#define PX4_ADC_GPIO \
/* BATTERY1_VOLTAGE GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_GPIO(0, 27), \
/* BATTERY1_CURRENT GPIO_AD_B0_12 GPIO1 Pin 12 */ ADC1_GPIO(1, 12), \
/* BATTERY2_VOLTAGE GPIO_AD_B0_13 GPIO1 Pin 13 */ ADC1_GPIO(2, 13), \
/* BATTERY2_CURRENT GPIO_AD_B0_14 GPIO1 Pin 14 */ ADC1_GPIO(3, 14), \
/* SPARE_2_CHANNEL GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_GPIO(4, 15), \
/* HW_VER_SENSE GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20), \
/* SCALED_V5 GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_GPIO(10, 21), \
/* SCALED_VDD_3V3_SENSORS GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_GPIO(11, 22), \
/* HW_REV_SENSE GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24), \
/* SPARE_1 GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_GPIO(14, 25), \
/* RSSI_IN GPIO_AD_B1_10 GPIO1 Pin 26 */ ADC1_GPIO(15, 26)
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY1_VOLTAGE_CHANNEL /* GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_CH(0)
#define ADC_BATTERY1_CURRENT_CHANNEL /* GPIO_AD_B0_12 GPIO1 Pin 12 */ ADC1_CH(1)
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* GPIO_AD_B0_13 GPIO1 Pin 13 */ ADC1_CH(2)
#define ADC_BATTERY2_CURRENT_CHANNEL /* GPIO_AD_B0_14 GPIO1 Pin 14 */ ADC1_CH(3)
#define ADC1_SPARE_2_CHANNEL /* GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_CH(4)
#define ADC_HW_VER_SENSE_CHANNEL /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_CH(9)
#define ADC_SCALED_V5_CHANNEL /* GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_CH(10)
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_CH(11)
#define ADC_HW_REV_SENSE_CHANNEL /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_CH(13)
#define ADC1_SPARE_1_CHANNEL /* GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_CH(14)
#define ADC_RSSI_IN_CHANNEL /* GPIO_AD_B1_10 GPIO1 Pin 26 */ ADC1_CH(15)
#define ADC_CHANNELS \
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
(1 << ADC1_SPARE_2_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
(1 << ADC1_SPARE_1_CHANNEL))
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define HW_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST)
#define GPIO_HW_VER_REV_DRIVE /* GPIO_AD_B0_01 GPIO1_IO01 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | HW_IOMUX)
#define GPIO_HW_REV_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24)
#define GPIO_HW_VER_SENSE /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20)
#define HW_INFO_INIT_PREFIX "V5"
#define V500 HW_VER_REV(0x0,0x0) // FMUV5, Rev 0
#define V540 HW_VER_REV(0x4,0x0) // mini no can 2,3, Rev 0
/* CAN Silence
*
* Silent mode control \ ESC Mux select
*/
#define SILENT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST)
#define GPIO_CAN1_SILENT_S0 /* GPIO_AD_B0_10 GPIO1_IO10 */ (GPIO_PORT1 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | SILENT_IOMUX)
#define GPIO_CAN2_SILENT_S1 /* GPIO_EMC_06 GPIO4_IO06 */ (GPIO_PORT4 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | SILENT_IOMUX)
#define GPIO_CAN3_SILENT_S2 /* GPIO_EMC_09 GPIO4_IO09 */ (GPIO_PORT4 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | SILENT_IOMUX)
/* HEATER
* PWM in future
*/
#define HEATER_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define GPIO_HEATER_OUTPUT /* GPIO_B1_09 QTIMER2_TIMER3 GPIO2_IO25 */ (GPIO_QTIMER2_TIMER3_1 | HEATER_IOMUX)
#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true))
/* PWM Capture
*
* 2 PWM Capture inputs are supported
*/
#define DIRECT_PWM_CAPTURE_CHANNELS 2
#define CAP_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define PIN_FLEXPWM2_PWMB0 /* P2:7 PWM2 B0 FMU_CAP1 */ (CAP_IOMUX | GPIO_FLEXPWM2_PWMB00_2)
#define PIN_FLEXPWM2_PWMB3 /* P3:3 PWM2 A1 FMU_CAP2 */ (CAP_IOMUX | GPIO_FLEXPWM2_PWMB03_3)
#define nARMED_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ)
#define nARMED_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define GPIO_nARMED_INIT /* GPIO_SD_B1_01 GPIO3_IO1 */ (GPIO_PORT3 | GPIO_PIN1 | GPIO_INPUT | nARMED_INPUT_IOMUX)
#define GPIO_nARMED /* GPIO_SD_B1_01 GPIO3_IO1 */ (GPIO_PORT3 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | nARMED_OUTPUT_IOMUX)
#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT)
#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_NUM_IO_TIMERS 8
// Input Capture not supported on MVP
#define BOARD_HAS_NO_CAPTURE
//#define BOARD_HAS_UI_LED_PWM 1 Not ported yet (Still Kinetis driver)
#define BOARD_HAS_LED_PWM 1
#define BOARD_LED_PWM_DRIVE_ACTIVE_LOW 1
/* UI LEDs are driven by timer 4 the pins have no alternates
*
* nUI_LED_RED GPIO_B0_10 GPIO2_IO10 QTIMER4_TIMER1
* nUI_LED_GREEN GPIO_B0_11 GPIO2_IO11 QTIMER4_TIMER2
* nUI_LED_BLUE GPIO_B1_11 GPIO2_IO27 QTIMER4_TIMER3
*/
/* Power supply control and monitoring GPIOs */
#define GENERAL_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ)
#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define GPIO_nPOWER_IN_A /* GPIO_B0_12 GPIO2_IO12 */ (GPIO_PORT2 | GPIO_PIN12 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_B /* GPIO_B0_13 GPIO2_IO13 */ (GPIO_PORT2 | GPIO_PIN13 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_C /* GPIO_B0_14 GPIO2_IO14 */ (GPIO_PORT2 | GPIO_PIN14 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */
#define BOARD_NUMBER_BRICKS 2
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
#define OC_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ)
#define GPIO_nVDD_5V_PERIPH_EN /* GPIO_B1_03 GPIO2_IO19 */ (GPIO_PORT2 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define GPIO_nVDD_5V_PERIPH_OC /* GPIO_B1_04 GPIO2_IO20 */ (GPIO_PORT2 | GPIO_PIN20 | GPIO_INPUT | OC_INPUT_IOMUX)
#define GPIO_nVDD_5V_HIPOWER_EN /* GPIO_B1_01 GPIO2_IO17 */ (GPIO_PORT2 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define GPIO_nVDD_5V_HIPOWER_OC /* GPIO_B1_02 GPIO2_IO18 */ (GPIO_PORT2 | GPIO_PIN18 | GPIO_INPUT | OC_INPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS_EN /* GPIO_EMC_41 GPIO3_IO27 */ (GPIO_PORT3 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* GPIO_AD_B0_00 GPIO1_IO00 */ (GPIO_PORT1 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_5V_RC_EN /* GPIO_AD_B0_08 GPIO1_IO08 */ (GPIO_PORT1 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_5V_WIFI_EN /* PMIC_STBY_REQ GPIO5_IO02 */ (GPIO_PORT5 | GPIO_PIN2 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SD_CARD_EN /* GPIO_EMC_13 GPIO4_IO13 */ (GPIO_PORT4 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO |GENERAL_OUTPUT_IOMUX)
/* Define True logic Power Control in arch agnostic form */
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_HIPOWER_EN, !(on_true))
#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true))
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true))
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
#define VDD_5V_RC_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true))
#define VDD_5V_WIFI_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_WIFI_EN, (on_true))
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
/* Tone alarm output */
#define TONE_ALARM_TIMER 2 /* GPT 2 */
#define TONE_ALARM_CHANNEL 3 /* GPIO_AD_B1_07 GPT2_COMPARE3 */
#define GPIO_BUZZER_1 /* GPIO_AD_B1_07 GPIO1_IO23 */ (GPIO_PORT1 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM (GPIO_GPT2_COMPARE3_2 | GENERAL_OUTPUT_IOMUX)
/* USB OTG FS
*
* VBUS_VALID is detected in USB_ANALOG_USB1_VBUS_DETECT_STAT
*/
/* High-resolution timer */
#define HRT_TIMER 1 /* use GPT1 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define HRT_PPM_CHANNEL /* GPIO_B1_06 GPT1_CAPTURE2 */ 2 /* use capture/compare channel 2 */
#define GPIO_PPM_IN /* GPIO_B1_06 GPT1_CAPTURE2 */ (GPIO_GPT1_CAPTURE2_2 | GENERAL_INPUT_IOMUX)
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_33 GPIO3_IO19 FLEXPWM3_PWMA2 */
#define PWMIN_TIMER /* FLEXPWM3_PWMA2 */ 3
#define PWMIN_TIMER_CHANNEL /* FLEXPWM3_PWMA2 */ 2
#define GPIO_PWM_IN /* GPIO_EMC_33 GPIO3_IO19 */ (GPIO_FLEXPWM3_PWMA02_1 | GENERAL_INPUT_IOMUX)
/* Shared pins Both FMU and PX4IO control/monitor
* FMU Initializes these pins to passive input until it is known
* if we have and PX4IO on board
*/
#define GPIO_RSSI_IN /* GPIO_AD_B1_10 GPIO1_IO26 */ (GPIO_PORT1 | GPIO_PIN26 | GPIO_INPUT | ADC_IOMUX)
#define GPIO_RSSI_IN_INIT /* GPIO_AD_B1_10 GPIO1_IO26 */ 0 /* Using 0 will Leave as ADC RSSI_IN */
/* Safety Switch is HW version dependent on having an PX4IO
* So we init to a benign state with the _INIT definition
* and provide the the non _INIT one for the driver to make a run time
* decision to use it.
*/
#define SAFETY_INIT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ)
#define SAFETY_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW)
#define SAFETY_SW_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ)
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* GPIO_B0_15 GPIO2_IO15 */ (GPIO_PORT2 | GPIO_PIN15 | GPIO_INPUT | SAFETY_INIT_IOMUX)
#define GPIO_nSAFETY_SWITCH_LED_OUT /* GPIO_B0_15 GPIO2_IO15 */ (GPIO_PORT2 | GPIO_PIN15 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | SAFETY_IOMUX)
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
#define GPIO_SAFETY_SWITCH_IN /* GPIO_AD_B1_12 GPIO1_IO28 */ (GPIO_PORT1 | GPIO_PIN28 | GPIO_INPUT | SAFETY_SW_IOMUX)
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
/*
* FMUv5 has a separate RC_IN
*
* GPIO PPM_IN on GPIO_EMC_23 GPIO4 Pin 23 GPT1_CAPTURE2
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
*/
#define GPIO_PPM_IN_AS_OUT /* GPIO_B1_06 GPIO2_IO23 GPT1_CAPTURE2 GPT1_CAPTURE2 */ (GPIO_PORT2 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
*/
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0)
/* FMUv5 never powers odd the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_HIPOWER_OC))
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
GPIO_nARMED_INIT, \
PX4_ADC_GPIO, \
GPIO_HW_VER_REV_DRIVE, \
GPIO_FLEXCAN1_TX, \
GPIO_FLEXCAN1_RX, \
GPIO_FLEXCAN2_TX, \
GPIO_FLEXCAN2_RX, \
GPIO_FLEXCAN3_TX, \
GPIO_FLEXCAN3_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_CAN2_SILENT_S1, \
GPIO_CAN3_SILENT_S2, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
GPIO_nPOWER_IN_C, \
GPIO_nVDD_5V_PERIPH_EN, \
GPIO_nVDD_5V_PERIPH_OC, \
GPIO_nVDD_5V_HIPOWER_EN, \
GPIO_nVDD_5V_HIPOWER_OC, \
GPIO_VDD_3V3_SENSORS_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_VDD_5V_RC_EN, \
GPIO_VDD_5V_WIFI_EN, \
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN_INIT, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_nSPI4_RESET_EXTERNAL1, \
GPIO_SPI4_SYNC_EXTERNAL1, \
GPIO_SAFETY_SWITCH_IN \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: fmurt1062_usdhc_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int fmurt1062_usdhc_initialize(void);
/****************************************************************************************************
* Name: imxrt_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
****************************************************************************************************/
extern void imxrt_spidev_initialize(void);
/************************************************************************************
* Name: imxrt_spi_bus_initialize
*
* Description:
* Called to configure SPI Buses.
*
************************************************************************************/
extern int imxrt1062_spi_bus_initialize(void);
/************************************************************************************
* Name: imxrt_usb_initialize
*
* Description:
* Called to configure USB.
*
************************************************************************************/
extern int imxrt_usb_initialize(void);
extern void imxrt_usbinitialize(void);
extern void board_peripheral_reset(int ms);
extern void fmurt1062_timer_initialize(void);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
@@ -33,11 +33,8 @@
#include <px4_arch/i2c_hw_description.h>
#if defined(CONFIG_I2C)
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(1),
initI2CBusExternal(2),
initI2CBusInternal(3),
initI2CBusExternal(6),
};
#endif
@@ -1,6 +1,8 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_boot.c
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -12,7 +14,7 @@
* 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
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,43 +33,32 @@
*
****************************************************************************/
#pragma once
/****************************************************************************
* Included Files
****************************************************************************/
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include "imxrt_flexspi_nor_boot.h"
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
/****************************************************************************
* Public Data
****************************************************************************/
#include "srv_base.h"
/**
* @see SrvBase
* @class VehicleCommandSrv The VehicleCommandSrv class implement the VehicleCommand service server.
*/
class VehicleCommandSrv : public SrvBase
{
private:
uORB::Publication<vehicle_command_s> vehicle_command_pub_{ORB_ID(vehicle_command)};
uORB::Subscription vehicle_command_ack_sub_{ORB_ID(vehicle_command_ack)};
uint32_t last_command_sent_{0};
hrt_abstime last_command_sent_timestamp_{0};
public:
/**
* @brief Constructor.
* @see SrvBase.
* @param client_namespace namespace for the client service.
* @param index index used to create the replier id.
* @return Returns false iff successful, otherwise false.
*/
VehicleCommandSrv(uxrSession *session, uxrStreamId reliable_out_stream_id, uxrStreamId input_stream_id,
uxrObjectId participant_id, const char *client_namespace, const uint8_t index);
~VehicleCommandSrv();
/** @see SrvBase */
bool process_request(ucdrBuffer *ub, const int64_t time_offset_us);
/** @see SrvBase */
bool process_reply();
__attribute__((section(".boot_hdr.ivt")))
const struct ivt_s g_image_vector_table = {
IVT_HEADER, /* IVT Header */
IMAGE_ENTRY_ADDRESS, /* Image Entry Function */
IVT_RSVD, /* Reserved = 0 */
(uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */
(uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */
(uint32_t)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */
(uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */
IVT_RSVD /* Reserved = 0 */
};
__attribute__((section(".boot_hdr.boot_data")))
const struct boot_data_s g_boot_data = {
IMAGE_DEST, /* boot start location */
(IMAGE_DEST_END - IMAGE_DEST), /* size */
PLUGIN_FLAG, /* Plugin flag */
0xffffffff /* empty - extra data word */
};
@@ -1,25 +1,41 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_boot.h
* boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexspi_nor_boot.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* http://www.apache.org/licenses/LICENSE-2.0
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
#define __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
#ifndef __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
#define __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
/****************************************************************************
* Included Files
@@ -58,8 +74,8 @@
#define DCD_VERSION (0x40)
#define DCD_ARRAY_SIZE 1
#define FLASH_BASE 0x30000000
#define FLASH_END FLASH_BASE + (3 * (1024*1024)) // We have 64M but we do not want to wait to program it all
#define FLASH_BASE 0x60000000
#define FLASH_END 0x7f7fffff
/* This needs to take into account the memory configuration at boot bootloader */
@@ -144,7 +160,7 @@ struct boot_data_s {
uint32_t start; /* boot start location */
uint32_t size; /* size */
uint32_t plugin; /* plugin flag - 1 if downloaded application is plugin */
uint32_t placeholder; /* placeholder to make even 0x10 size */
uint32_t placeholder; /* placehoder to make even 0x10 size */
};
/****************************************************************************
@@ -152,7 +168,8 @@ struct boot_data_s {
****************************************************************************/
extern const struct boot_data_s g_boot_data;
extern const uint8_t g_dcd_data[];
extern const uint32_t _vectors[];
extern const uint8_t g_dcd_data[];
extern const uint32_t _vectors[];
#endif /* __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */
#endif /* __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */
@@ -0,0 +1,198 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.c
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*******************************************************************************
* Included Files
******************************************************************************/
#include "imxrt_flexspi_nor_flash.h"
/*******************************************************************************
* Public Data
******************************************************************************/
#if defined (CONFIG_NXP_FMURT1062_V3_HYPER_FLASH)
__attribute__((section(".boot_hdr.conf")))
const struct flexspi_nor_config_s g_flash_config = {
.mem_config =
{
.tag = FLEXSPI_CFG_BLK_TAG,
.version = FLEXSPI_CFG_BLK_VERSION,
.read_sample_clksrc = FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD,
.cs_hold_time = 3u,
.cs_setup_time = 3u,
.column_address_width = 3u,
/* Enable DDR mode, Word addassable, Safe configuration, Differential clock */
.controller_misc_option = (1u << FLEXSPIMISC_OFFSET_DDR_MODE_EN) |
(1u << FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN) |
(1u << FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN) |
(1u << FLEXSPIMISC_OFFSET_DIFFCLKEN),
.sflash_pad_type = SERIAL_FLASH_8PADS,
.serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_133MHz,
.sflash_a1size = 64u * 1024u * 1024u,
.data_valid_time = {16u, 16u},
.lookup_table =
{
/* Read LUTs */
FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xA0, RADDR_DDR, FLEXSPI_8PAD, 0x18),
FLEXSPI_LUT_SEQ(CADDR_DDR, FLEXSPI_8PAD, 0x10, DUMMY_DDR, FLEXSPI_8PAD, 0x06),
FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP, FLEXSPI_1PAD, 0x0),
},
},
.page_size = 512u,
.sector_size = 256u * 1024u,
.blocksize = 256u * 1024u,
.is_uniform_blocksize = 1,
};
#elif defined (CONFIG_NXP_FMURT1062_V3_QSPI_FLASH)
__attribute__((section(".boot_hdr.conf")))
const struct flexspi_nor_config_s g_flash_config = {
.mem_config =
{
.tag = FLEXSPI_CFG_BLK_TAG,
.version = FLEXSPI_CFG_BLK_VERSION,
.read_sample_clksrc = FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD,
.cs_hold_time = 3u,
.cs_setup_time = 3u,
.column_address_width = 0u,
.device_type = FLEXSPI_DEVICE_TYPE_SERIAL_NOR,
.sflash_pad_type = SERIAL_FLASH_4PADS,
.serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_60MHz,
.sflash_a1size = 8u * 1024u * 1024u,
.data_valid_time = {16u, 16u},
.lookup_table =
{
/* LUTs */
/* 0 Fast read Quad IO DTR Mode Operation in SPI Mode (normal read)*/
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xED, RADDR_DDR, FLEXSPI_4PAD, 0x18),
FLEXSPI_LUT_SEQ(DUMMY_DDR, FLEXSPI_4PAD, 0x0C, READ_DDR, FLEXSPI_4PAD, 0x08),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 1 Read Status */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x05, READ_SDR, FLEXSPI_1PAD, 0x1),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 2 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 3 */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 4 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 5 Erase Sector */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xD7, RADDR_SDR, FLEXSPI_1PAD, 0x18),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 6 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 7 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 8 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 9 Page Program */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x02, RADDR_SDR, FLEXSPI_1PAD, 0x18),
FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_1PAD, 0x8, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 10 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 11 Chip Erase */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xC7, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
},
},
.page_size = 256u,
.sector_size = 4u * 1024u,
.blocksize = 32u * 1024u,
.is_uniform_blocksize = false,
};
#else
# error Boot Flash type not chosen!
#endif
@@ -0,0 +1,349 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
#define __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* FLEXSPI memory config block related defintions */
#define FLEXSPI_CFG_BLK_TAG (0x42464346ul)
#define FLEXSPI_CFG_BLK_VERSION (0x56010400ul)
#define FLEXSPI_CFG_BLK_SIZE (512)
/* FLEXSPI Feature related definitions */
#define FLEXSPI_FEATURE_HAS_PARALLEL_MODE 1
/* Lookup table related defintions */
#define CMD_INDEX_READ 0
#define CMD_INDEX_READSTATUS 1
#define CMD_INDEX_WRITEENABLE 2
#define CMD_INDEX_WRITE 4
#define CMD_LUT_SEQ_IDX_READ 0
#define CMD_LUT_SEQ_IDX_READSTATUS 1
#define CMD_LUT_SEQ_IDX_WRITEENABLE 3
#define CMD_LUT_SEQ_IDX_WRITE 9
#define CMD_SDR 0x01
#define CMD_DDR 0x21
#define RADDR_SDR 0x02
#define RADDR_DDR 0x22
#define CADDR_SDR 0x03
#define CADDR_DDR 0x23
#define MODE1_SDR 0x04
#define MODE1_DDR 0x24
#define MODE2_SDR 0x05
#define MODE2_DDR 0x25
#define MODE4_SDR 0x06
#define MODE4_DDR 0x26
#define MODE8_SDR 0x07
#define MODE8_DDR 0x27
#define WRITE_SDR 0x08
#define WRITE_DDR 0x28
#define READ_SDR 0x09
#define READ_DDR 0x29
#define LEARN_SDR 0x0a
#define LEARN_DDR 0x2a
#define DATSZ_SDR 0x0b
#define DATSZ_DDR 0x2b
#define DUMMY_SDR 0x0c
#define DUMMY_DDR 0x2c
#define DUMMY_RWDS_SDR 0x0d
#define DUMMY_RWDS_DDR 0x2d
#define JMP_ON_CS 0x1f
#define STOP 0
#define FLEXSPI_1PAD 0
#define FLEXSPI_2PAD 1
#define FLEXSPI_4PAD 2
#define FLEXSPI_8PAD 3
#define FLEXSPI_LUT_OPERAND0_MASK (0xffu)
#define FLEXSPI_LUT_OPERAND0_SHIFT (0U)
#define FLEXSPI_LUT_OPERAND0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND0_SHIFT)) & \
FLEXSPI_LUT_OPERAND0_MASK)
#define FLEXSPI_LUT_NUM_PADS0_MASK (0x300u)
#define FLEXSPI_LUT_NUM_PADS0_SHIFT (8u)
#define FLEXSPI_LUT_NUM_PADS0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS0_SHIFT)) & \
FLEXSPI_LUT_NUM_PADS0_MASK)
#define FLEXSPI_LUT_OPCODE0_MASK (0xfc00u)
#define FLEXSPI_LUT_OPCODE0_SHIFT (10u)
#define FLEXSPI_LUT_OPCODE0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE0_SHIFT)) & \
FLEXSPI_LUT_OPCODE0_MASK)
#define FLEXSPI_LUT_OPERAND1_MASK (0xff0000u)
#define FLEXSPI_LUT_OPERAND1_SHIFT (16U)
#define FLEXSPI_LUT_OPERAND1(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND1_SHIFT)) & \
FLEXSPI_LUT_OPERAND1_MASK)
#define FLEXSPI_LUT_NUM_PADS1_MASK (0x3000000u)
#define FLEXSPI_LUT_NUM_PADS1_SHIFT (24u)
#define FLEXSPI_LUT_NUM_PADS1(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS1_SHIFT)) & \
FLEXSPI_LUT_NUM_PADS1_MASK)
#define FLEXSPI_LUT_OPCODE1_MASK (0xfc000000u)
#define FLEXSPI_LUT_OPCODE1_SHIFT (26u)
#define FLEXSPI_LUT_OPCODE1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE1_SHIFT)) & \
FLEXSPI_LUT_OPCODE1_MASK)
#define FLEXSPI_LUT_SEQ(cmd0, pad0, op0, cmd1, pad1, op1) \
(FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | \
FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \
FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1))
/* */
#define NOR_CMD_INDEX_READ CMD_INDEX_READ
#define NOR_CMD_INDEX_READSTATUS CMD_INDEX_READSTATUS
#define NOR_CMD_INDEX_WRITEENABLE CMD_INDEX_WRITEENABLE
#define NOR_CMD_INDEX_ERASESECTOR 3
#define NOR_CMD_INDEX_PAGEPROGRAM CMD_INDEX_WRITE
#define NOR_CMD_INDEX_CHIPERASE 5
#define NOR_CMD_INDEX_DUMMY 6
#define NOR_CMD_INDEX_ERASEBLOCK 7
/* READ LUT sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READ CMD_LUT_SEQ_IDX_READ
/* Read Status LUT sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS CMD_LUT_SEQ_IDX_READSTATUS
/* 2 Read status DPI/QPI/OPI sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS_XPI 2
/* 3 Write Enable sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE CMD_LUT_SEQ_IDX_WRITEENABLE
/* 4 Write Enable DPI/QPI/OPI sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE_XPI 4
/* 5 Erase Sector sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_ERASESECTOR 5
/* 8 Erase Block sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_ERASEBLOCK 8
/* 9 Program sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_PAGEPROGRAM CMD_LUT_SEQ_IDX_WRITE
/* 11 Chip Erase sequence in lookupTable id stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_CHIPERASE 11
/* 13 Read SFDP sequence in lookupTable id stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READ_SFDP 13
/* 14 Restore 0-4-4/0-8-8 mode sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_RESTORE_NOCMD 14
/* 15 Exit 0-4-4/0-8-8 mode sequence id in lookupTable stored in config blobk */
#define NOR_CMD_LUT_SEQ_IDX_EXIT_NOCMD 15
/****************************************************************************
* Public Types
****************************************************************************/
/* Definitions for FlexSPI Serial Clock Frequency */
enum flexspi_serial_clkfreq_e {
FLEXSPI_SERIAL_CLKFREQ_30MHz = 1,
FLEXSPI_SERIAL_CLKFREQ_50MHz = 2,
FLEXSPI_SERIAL_CLKFREQ_60MHz = 3,
FLEXSPI_SERIAL_CLKFREQ_75MHz = 4,
FLEXSPI_SERIAL_CLKFREQ_80MHz = 5,
FLEXSPI_SERIAL_CLKFREQ_100MHz = 6,
FLEXSPI_SERIAL_CLKFREQ_133MHz = 7,
FLEXSPI_SERIAL_CLKFREQ_166MHz = 8,
FLEXSPI_SERIAL_CLKFREQ_200MHz = 9,
};
/* FlexSPI clock configuration type*/
enum flexspi_serial_clockmode_e {
FLEXSPI_CLKMODE_SDR,
FLEXSPI_CLKMODE_DDR,
};
/* FlexSPI Read Sample Clock Source definition */
enum flash_read_sample_clk_e {
FLASH_READ_SAMPLE_CLK_LOOPBACK_INTERNELLY = 0,
FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD = 1,
FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD = 2,
FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD = 3,
};
/* Misc feature bit definitions */
enum flash_misc_feature_e {
FLEXSPIMISC_OFFSET_DIFFCLKEN = 0, /* Bit for Differential clock enable */
FLEXSPIMISC_OFFSET_CK2EN = 1, /* Bit for CK2 enable */
FLEXSPIMISC_OFFSET_PARALLELEN = 2, /* Bit for Parallel mode enable */
FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN = 3, /* Bit for Word Addressable enable */
FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN = 4, /* Bit for Safe Configuration Frequency enable */
FLEXSPIMISC_OFFSET_PAD_SETTING_OVERRIDE_EN = 5, /* Bit for Pad setting override enable */
FLEXSPIMISC_OFFSET_DDR_MODE_EN = 6, /* Bit for DDR clock confiuration indication. */
};
/* Flash Type Definition */
enum flash_flash_type_e {
FLEXSPI_DEVICE_TYPE_SERIAL_NOR = 1, /* Flash devices are Serial NOR */
FLEXSPI_DEVICE_TYPE_SERIAL_NAND = 2, /* Flash devices are Serial NAND */
FLEXSPI_DEVICE_TYPE_SERIAL_RAM = 3, /* Flash devices are Serial RAM/HyperFLASH */
FLEXSPI_DEVICE_TYPE_MCP_NOR_NAND = 0x12, /* Flash device is MCP device, A1 is Serial NOR, A2 is Serial NAND */
FLEXSPI_DEVICE_TYPE_MCP_NOR_RAM = 0x13, /* Flash deivce is MCP device, A1 is Serial NOR, A2 is Serial RAMs */
};
/* Flash Pad Definitions */
enum flash_flash_pad_e {
SERIAL_FLASH_1PAD = 1,
SERIAL_FLASH_2PADS = 2,
SERIAL_FLASH_4PADS = 4,
SERIAL_FLASH_8PADS = 8,
};
/* Flash Configuration Command Type */
enum flash_config_cmd_e {
DEVICE_CONFIG_CMD_TYPE_GENERIC, /* Generic command, for example: configure dummy cycles, drive strength, etc */
DEVICE_CONFIG_CMD_TYPE_QUADENABLE, /* Quad Enable command */
DEVICE_CONFIG_CMD_TYPE_SPI2XPI, /* Switch from SPI to DPI/QPI/OPI mode */
DEVICE_CONFIG_CMD_TYPE_XPI2SPI, /* Switch from DPI/QPI/OPI to SPI mode */
DEVICE_CONFIG_CMD_TYPE_SPI2NO_CMD, /* Switch to 0-4-4/0-8-8 mode */
DEVICE_CONFIG_CMD_TYPE_RESET, /* Reset device command */
};
/* FlexSPI LUT Sequence structure */
struct flexspi_lut_seq_s {
uint8_t seq_num; /* Sequence Number, valid number: 1-16 */
uint8_t seq_id; /* Sequence Index, valid number: 0-15 */
uint16_t reserved;
};
/* FlexSPI Memory Configuration Block */
struct flexspi_mem_config_s {
uint32_t tag;
uint32_t version;
uint32_t reserved0;
uint8_t read_sample_clksrc;
uint8_t cs_hold_time;
uint8_t cs_setup_time;
uint8_t column_address_width; /* [0x00f-0x00f] Column Address with, for
* HyperBus protocol, it is fixed to 3, For
* Serial NAND, need to refer to datasheet */
uint8_t device_mode_cfg_enable;
uint8_t device_mode_type;
uint16_t wait_time_cfg_commands;
struct flexspi_lut_seq_s device_mode_seq;
uint32_t device_mode_arg;
uint8_t config_cmd_enable;
uint8_t config_mode_type[3];
struct flexspi_lut_seq_s config_cmd_seqs[3];
uint32_t reserved1;
uint32_t config_cmd_args[3];
uint32_t reserved2;
uint32_t controller_misc_option;
uint8_t device_type;
uint8_t sflash_pad_type;
uint8_t serial_clk_freq;
uint8_t lut_custom_seq_enable;
uint32_t reserved3[2];
uint32_t sflash_a1size;
uint32_t sflash_a2size;
uint32_t sflash_b1size;
uint32_t sflash_b2size;
uint32_t cspad_setting_override;
uint32_t sclkpad_setting_override;
uint32_t datapad_setting_override;
uint32_t dqspad_setting_override;
uint32_t timeout_in_ms;
uint32_t command_interval;
uint16_t data_valid_time[2];
uint16_t busy_offset;
uint16_t busybit_polarity;
uint32_t lookup_table[64];
struct flexspi_lut_seq_s lut_customseq[12];
uint32_t reserved4[4];
};
/* Serial NOR configuration block */
struct flexspi_nor_config_s {
struct flexspi_mem_config_s mem_config; /* Common memory configuration info via FlexSPI */
uint32_t page_size; /* Page size of Serial NOR */
uint32_t sector_size; /* Sector size of Serial NOR */
uint8_t ipcmd_serial_clkfreq; /* Clock frequency for IP command */
uint8_t is_uniform_blocksize; /* Sector/Block size is the same */
uint8_t reserved0[2]; /* Reserved for future use */
uint8_t serial_nor_type; /* Serial NOR Flash type: 0/1/2/3 */
uint8_t need_exit_nocmdmode; /* Need to exit NoCmd mode before other IP command */
uint8_t halfclk_for_nonreadcmd; /* Half the Serial Clock for non-read command: true/false */
uint8_t need_restore_nocmdmode; /* Need to Restore NoCmd mode after IP commmand execution */
uint32_t blocksize; /* Block size */
uint32_t reserve2[11]; /* Reserved for future use */
};
#endif /* __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2018-2019, 2023 PX4 Development Team. All rights reserved.
* Copyright (c) 2018-2019 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
@@ -34,7 +34,7 @@
/**
* @file init.c
*
* PX4 fmu-v6xrt specific early startup code. This file implements the
* NXP imxrt1062-v1 specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
@@ -47,7 +47,6 @@
#include "board_config.h"
#include <barriers.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
@@ -64,18 +63,14 @@
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include "arm_internal.h"
#include "arm_internal.h"
#include "imxrt_flexspi_nor_boot.h"
#include "imxrt_flexspi_nor_flash.h"
#include "imxrt_romapi.h"
#include "imxrt_iomuxc.h"
#include "imxrt_flexcan.h"
#include "imxrt_enet.h"
#include <chip.h>
#include "board_config.h"
#include <hardware/imxrt_lpuart.h>
#undef FLEXSPI_LUT_COUNT
#include <hardware/imxrt_flexspi.h>
#include <arch/board/board.h>
@@ -105,14 +100,6 @@ __BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern uint32_t _srodata; /* Start of .rodata */
extern uint32_t _erodata; /* End of .rodata */
extern const uint64_t _fitcmfuncs; /* Copy source address in FLASH */
extern uint64_t _sitcmfuncs; /* Copy destination start address in ITCM */
extern uint64_t _eitcmfuncs; /* Copy destination end address in ITCM */
extern uint64_t _sdtcm; /* Copy destination start address in DTCM */
extern uint64_t _edtcm; /* Copy destination end address in DTCM */
__END_DECLS
/************************************************************************************
@@ -162,68 +149,7 @@ __EXPORT void board_on_reset(int status)
}
}
#if defined(CONFIG_BOARD_BOOTLOADER_FIXUP)
/****************************************************************************
* Name: imxrt_octl_flash_initialize
*
* Description:
*
****************************************************************************/
struct flexspi_nor_config_s g_bootConfig;
locate_code(".ramfunc")
void imxrt_octl_flash_initialize(void)
{
const uint32_t instance = 1;
memcpy((struct flexspi_nor_config_s *)&g_bootConfig, &g_flash_fast_config,
sizeof(struct flexspi_nor_config_s));
g_bootConfig.memConfig.tag = FLEXSPI_CFG_BLK_TAG;
ROM_API_Init();
ROM_FLEXSPI_NorFlash_Init(instance, (struct flexspi_nor_config_s *)&g_bootConfig);
ROM_FLEXSPI_NorFlash_ClearCache(1);
ARM_DSB();
ARM_ISB();
ARM_DMB();
}
#endif
locate_code(".ramfunc")
void imxrt_flash_setup_prefetch_partition(void)
{
putreg32((uint32_t)&_srodata, IMXRT_FLEXSPI1_AHBBUFREGIONSTART0);
putreg32((uint32_t)&_erodata, IMXRT_FLEXSPI1_AHBBUFREGIONEND0);
putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART1);
putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND1);
struct flexspi_type_s *g_flexspi = (struct flexspi_type_s *)IMXRT_FLEXSPIC_BASE;
/* RODATA */
g_flexspi->AHBRXBUFCR0[0] = FLEXSPI_AHBRXBUFCR0_BUFSZ(128) |
FLEXSPI_AHBRXBUFCR0_MSTRID(7) |
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
FLEXSPI_AHBRXBUFCR0_REGIONEN(1);
/* All Text */
g_flexspi->AHBRXBUFCR0[1] = FLEXSPI_AHBRXBUFCR0_BUFSZ(380) |
FLEXSPI_AHBRXBUFCR0_MSTRID(7) |
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
FLEXSPI_AHBRXBUFCR0_REGIONEN(1);
/* Reset CR7 from rom init */
g_flexspi->AHBRXBUFCR0[7] = FLEXSPI_AHBRXBUFCR0_BUFSZ(0) |
FLEXSPI_AHBRXBUFCR0_MSTRID(0) |
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
FLEXSPI_AHBRXBUFCR0_REGIONEN(0);
ARM_DSB();
ARM_ISB();
ARM_DMB();
}
/****************************************************************************
* Name: imxrt_ocram_initialize
*
@@ -235,53 +161,28 @@ void imxrt_flash_setup_prefetch_partition(void)
__EXPORT void imxrt_ocram_initialize(void)
{
uint32_t regval;
register uint64_t *src;
register uint64_t *dest;
/* Reallocate
* Final Configuration is
* No DTCM
* 512k OCRAM M7 (FlexRAM) (2038:0000-203f:ffff)
* 128k OCRAMM7 FlexRAM ECC (2036:0000-2037:ffff)
* 64k OCRAM2 ECC parity (2035:0000-2035:ffff)
* 64k OCRAM1 ECC parity (2034:0000-2034:ffff)
* 512k FlexRAM OCRAM2 (202C:0000-2033:ffff)
* 512k FlexRAM OCRAM1 (2024:0000-202B:ffff)
* 256k System OCRAM M4 (2020:0000-2023:ffff)
*/
putreg32(0x0000FFAA, IMXRT_IOMUXC_GPR_GPR17);
putreg32(0x0000FFAA, IMXRT_IOMUXC_GPR_GPR18);
regval = getreg32(IMXRT_IOMUXC_GPR_GPR16);
putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SEL_REG, IMXRT_IOMUXC_GPR_GPR16);
/* Copy any necessary code sections from FLASH to ITCM. The process is the
* same as the code copying from FLASH to RAM above. */
for (src = (uint64_t *)&_fitcmfuncs, dest = (uint64_t *)&_sitcmfuncs;
dest < (uint64_t *)&_eitcmfuncs;) {
*dest++ = *src++;
}
/* Clear .dtcm. We'll do this inline (vs. calling memset) just to be
* certain that there are no issues with the state of global variables.
*/
for (dest = &_sdtcm; dest < &_edtcm;) {
*dest++ = 0;
}
#if defined(CONFIG_BOOT_RUNFROMISRAM)
const uint32_t *src;
uint32_t *dest;
uint32_t regval;
/* Reallocate 128K of Flex RAM from ITCM to OCRAM
* Final Configuration is
* 128 DTCM
*
* 128 FlexRAM OCRAM (202C:0000-202D:ffff)
* 256 FlexRAM OCRAM (2028:0000-202B:ffff)
* 512 System OCRAM2 (2020:0000-2027:ffff)
* */
putreg32(0xaa555555, IMXRT_IOMUXC_GPR_GPR17);
regval = getreg32(IMXRT_IOMUXC_GPR_GPR16);
putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SELF, IMXRT_IOMUXC_GPR_GPR16);
for (src = (uint32_t *)(LOCATE_IN_SRC(g_boot_data.start) + g_boot_data.size),
dest = (uint32_t *)(g_boot_data.start + g_boot_data.size);
dest < (uint32_t *) &_etext;) {
*dest++ = *src++;
}
#endif
}
/****************************************************************************
@@ -298,12 +199,6 @@ __EXPORT void imxrt_ocram_initialize(void)
__EXPORT void imxrt_boardinitialize(void)
{
#if defined(CONFIG_BOARD_BOOTLOADER_FIXUP)
imxrt_octl_flash_initialize();
#endif
imxrt_flash_setup_prefetch_partition();
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
@@ -315,10 +210,13 @@ __EXPORT void imxrt_boardinitialize(void)
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
imxrt_spidev_initialize();
imxrt_usb_initialize();
fmuv6xrt_timer_initialize();
VDD_3V3_ETH_POWER_EN(true);
fmurt1062_timer_initialize();
}
@@ -346,51 +244,20 @@ __EXPORT void imxrt_boardinitialize(void)
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
int ret = OK;
#if !defined(BOOTLOADER)
/* Power on Interfaces */
VDD_3V3_SD_CARD_EN(true);
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
VDD_3V3_SENSORS_EN(true);
VDD_3V3_SPEKTRUM_POWER_EN(true);
/*
* We have BOARD_I2C_LATEINIT Defined to hold off the I2C init
* To enable SE050 driveHW_VER_REV_DRIVE low. But we have to ensure the
* EEROM version can be read first.
* Power on sequence:
* 1) Drive I2C4 lines to output low (avoid backfeeding SE050)
* 2) DoHWversioning withVDD_3V3_SENSORS4 off. LeaveHW_VER_REV_DRIVE high (SE050 disabled) on exit.
* 3) Then set HW_VER_REV_DRIVE low (SE050 enabled).
* 4) Then power onVDD_3V3_SENSORS4.
* 5) HW_VER_REV_DRIVE can be used to toggle SE050_ENAlater if needed.
*/
/* Step 1 */
px4_arch_gpiowrite(GPIO_LPI2C3_SCL, 0);
px4_arch_gpiowrite(GPIO_LPI2C3_SDA, 0);
px4_arch_gpiowrite(GPIO_HW_VER_REV_DRIVE, 1);
VDD_3V3_SENSORS4_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
imxrt_spiinitialize();
/* Configure the HW based on the manifest
* This will use I2C busses so VDD_3V3_SENSORS4_EN
* needs to be up.
*/
px4_platform_configure();
/* Step 2 */
board_spi_reset(10, 0xffff);
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
@@ -400,51 +267,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
/* Step 3 reset the SE550
* Power it down, prevetn back feeding
* and let it settle
*/
VDD_3V3_SENSORS4_EN(false);
px4_arch_gpiowrite(GPIO_LPI2C3_SCL, 0);
px4_arch_gpiowrite(GPIO_LPI2C3_SDA, 0);
px4_arch_gpiowrite(GPIO_HW_VER_REV_DRIVE, 1);
usleep(50000);
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
usleep(75000);
/* Step 4 */
VDD_3V3_SENSORS4_EN(true);
px4_arch_configgpio(GPIO_LPI2C3_SCL);
px4_arch_configgpio(GPIO_LPI2C3_SDA);
/* Enable the SE550 */
px4_arch_gpiowrite(GPIO_HW_VER_REV_DRIVE, 0);
/* CTS had been treated as inputs pulled high
* to avoid radios from enteriong bootloader
* Set them up as CTS inputs
*/
px4_arch_configgpio(GPIO_LPUART4_CTS);
px4_arch_configgpio(GPIO_LPUART8_CTS);
px4_arch_configgpio(GPIO_LPUART10_CTS);
/* Do the I2C init late BOARD_I2C_LATEINIT */
px4_platform_i2c_init();
/* Configure the Actual SPI interfaces (after we determined the HW version) */
imxrt_spiinitialize();
board_spi_reset(10, 0xffff);
px4_platform_init();
/* configure the DMA allocator */
@@ -452,7 +276,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if 0 // defined(SERIAL_HAVE_RXDMA)
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)imxrt_serial_dma_poll, NULL);
@@ -465,16 +289,9 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_off(LED_GREEN);
led_off(LED_BLUE);
#ifdef CONFIG_BOARD_CRASHDUMP
if (board_hardfault_init(2, true) != 0) {
led_on(LED_RED);
}
#endif
int ret = OK;
#if defined(CONFIG_IMXRT_USDHC)
ret = fmuv6xrt_usdhc_initialize();
ret = fmurt1062_usdhc_initialize();
if (ret != OK) {
led_on(LED_RED);
@@ -482,23 +299,17 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif
#ifdef CONFIG_IMXRT_ENET
imxrt_netinitialize(0);
#endif
/* Configure SPI-based devices */
#ifdef CONFIG_IMXRT_FLEXCAN1
imxrt_caninitialize(1);
#endif
ret = imxrt1062_spi_bus_initialize();
#ifdef CONFIG_IMXRT_FLEXCAN2
imxrt_caninitialize(2);
#endif
if (ret != OK) {
led_on(LED_RED);
}
#ifdef CONFIG_IMXRT_FLEXCAN3
imxrt_caninitialize(3);
#endif
/* Configure the HW based on the manifest */
#endif /* !defined(BOOTLOADER) */
px4_platform_configure();
return ret;
}
@@ -34,7 +34,7 @@
/**
* @file led.c
*
* PX4 fmu-v6rt LED backend.
* NXP fmurt1062-v1 LED backend.
*/
#include <px4_platform_common/px4_config.h>
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2018, 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -71,35 +71,25 @@ static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_V00[] = {
static const px4_hw_mft_item_t hw_mft_list_v0500[] = {
{
// PX4_MFT_PX4IO
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_USB
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN2
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN3
.present = 1,
.mandatory = 1,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_onboard,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0540[] = {
{
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{V6XRT_00, hw_mft_list_V00, arraySize(hw_mft_list_V00)},
{V500, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{V540, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
};
/************************************************************************************
@@ -91,14 +91,14 @@
****************************************************************************/
/****************************************************************************
* Name: fmuv6xrt_usdhc_initialize
* Name: fmurt1062_usdhc_initialize
*
* Description:
* Inititialize the SDHC SD card slot
*
****************************************************************************/
int fmuv6xrt_usdhc_initialize(void)
int fmurt1062_usdhc_initialize(void)
{
int ret;
+388
View File
@@ -0,0 +1,388 @@
/************************************************************************************
*
* Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_config.h>
#include <px4_log.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <systemlib/px4_macros.h>
#include <px4_platform/gpio.h>
#include <arm_internal.h>
#include <chip.h>
#include "imxrt_lpspi.h"
#include "imxrt_gpio.h"
#include "board_config.h"
#include <systemlib/err.h>
#if defined(CONFIG_IMXRT_LPSPI1) || defined(CONFIG_IMXRT_LPSPI2) || \
defined(CONFIG_IMXRT_LPSPI3) || defined(CONFIG_IMXRT_LPSPI4)
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::Port3, GPIO::Pin26}, SPI::DRDY{GPIO::Port4, GPIO::Pin15}), /* GPIO_EMC_40 GPIO3_IO26 */
initSPIDevice(DRV_GYR_DEVTYPE_BMI055, SPI::CS{GPIO::Port2, GPIO::Pin26}, SPI::DRDY{GPIO::Port4, GPIO::Pin16}), /* GPIO_B1_10 GPIO2_IO26 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI055, SPI::CS{GPIO::Port2, GPIO::Pin31}, SPI::DRDY{GPIO::Port3, GPIO::Pin23}), /* GPIO_B1_15 GPIO2_IO31 */
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::Port3, GPIO::Pin0}), /* GPIO_SD_B1_00 GPIO3_IO00, AUX_MEM */
}, {GPIO::Port3, GPIO::Pin27}),
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::Port3, GPIO::Pin20}) /* GPIO_EMC_34 G GPIO3_IO20 */
}),
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::Port4, GPIO::Pin14}), /* GPIO_EMC_14 GPIO4_IO14 */
}),
initSPIBusExternal(SPI::Bus::LPSPI4, {
initSPIConfigExternal(SPI::CS{GPIO::Port4, GPIO::Pin7}), /* GPIO_EMC_07 GPIO4_IO07 */
initSPIConfigExternal(SPI::CS{GPIO::Port2, GPIO::Pin30}), /* GPIO_B1_14 GPIO2_IO30 */
initSPIConfigExternal(SPI::CS{GPIO::Port4, GPIO::Pin11}), /* GPIO_EMC_11 GPIO4_IO011 */
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT))
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: fmurt1062_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board.
*
************************************************************************************/
void imxrt_spidev_initialize(void)
{
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
px4_arch_configgpio(px4_spi_buses[bus].devices[i].cs_gpio);
}
}
}
}
/************************************************************************************
* Name: imxrt_spi_bus_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board.
*
************************************************************************************/
static const px4_spi_bus_t *_spi_bus1;
static const px4_spi_bus_t *_spi_bus2;
static const px4_spi_bus_t *_spi_bus3;
static const px4_spi_bus_t *_spi_bus4;
__EXPORT int imxrt1062_spi_bus_initialize(void)
{
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
switch (px4_spi_buses[i].bus) {
case 1: _spi_bus1 = &px4_spi_buses[i]; break;
case 2: _spi_bus2 = &px4_spi_buses[i]; break;
case 3: _spi_bus3 = &px4_spi_buses[i]; break;
case 4: _spi_bus4 = &px4_spi_buses[i]; break;
}
}
/* Configure SPI-based devices */
struct spi_dev_s *spi_sensors = px4_spibus_initialize(1);
if (!spi_sensors) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 1);
return -ENODEV;
}
/* Default bus 1 to 1MHz and de-assert the known chip selects.
*/
SPI_SETFREQUENCY(spi_sensors, 1 * 1000 * 1000);
SPI_SETBITS(spi_sensors, 8);
SPI_SETMODE(spi_sensors, SPIDEV_MODE3);
/* Get the SPI port for the Memory */
struct spi_dev_s *spi_memory = px4_spibus_initialize(2);
if (!spi_memory) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 2);
return -ENODEV;
}
/* Default PX4_SPI_BUS_MEMORY to 12MHz and de-assert the known chip selects.
*/
SPI_SETFREQUENCY(spi_memory, 12 * 1000 * 1000);
SPI_SETBITS(spi_memory, 8);
SPI_SETMODE(spi_memory, SPIDEV_MODE3);
/* Get the SPI port for the BARO */
struct spi_dev_s *spi_baro = px4_spibus_initialize(3);
if (!spi_baro) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 3);
return -ENODEV;
}
/* MS5611 has max SPI clock speed of 20MHz
*/
SPI_SETFREQUENCY(spi_baro, 20 * 1000 * 1000);
SPI_SETBITS(spi_baro, 8);
SPI_SETMODE(spi_baro, SPIDEV_MODE3);
/* Get the SPI port for the PX4_SPI_EXTERNAL1 */
struct spi_dev_s *spi_ext = px4_spibus_initialize(4);
if (!spi_ext) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 4);
return -ENODEV;
}
/* Default ext bus to 1MHz and de-assert the known chip selects.
*/
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
SPI_SETBITS(spi_ext, 8);
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
/* deselect all */
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
}
}
}
return OK;
}
/****************************************************************************
* Name: imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status
*
* Description:
* The external functions, imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status must be
* provided by board-specific logic. They are implementations of the select
* and status methods of the SPI interface defined by struct spi_ops_s (see
* include/nuttx/spi/spi.h). All other methods (including imxrt_lpspibus_initialize())
* are provided by common STM32 logic. To use this common SPI logic on your
* board:
*
* 1. Provide logic in imxrt_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide imxrt_lpspi1/2/3select() and imxrt_lpspi1/2/3status() functions in your
* board-specific logic. These functions will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 3. Add a calls to imxrt_lpspibus_initialize() in your low level application
* initialization logic
* 4. The handle returned by imxrt_lpspibus_initialize() may then be used to bind the
* SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
****************************************************************************/
static inline void imxrt_spixselect(const px4_spi_bus_t *bus, struct spi_dev_s *dev, uint32_t devid, bool selected)
{
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
if (bus->devices[i].cs_gpio == 0) {
break;
}
if (devid == bus->devices[i].devid) {
// SPI select is active low, so write !selected to select the device
imxrt_gpio_write(bus->devices[i].cs_gpio, !selected);
}
}
}
#if defined(CONFIG_IMXRT_LPSPI1)
__EXPORT void imxrt_lpspi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
imxrt_spixselect(_spi_bus1, dev, devid, selected);
}
__EXPORT uint8_t imxrt_lpspi1status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI2)
__EXPORT void imxrt_lpspi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
imxrt_spixselect(_spi_bus2, dev, devid, selected);
}
__EXPORT uint8_t imxrt_lpspi2status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI3)
__EXPORT void imxrt_lpspi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
imxrt_spixselect(_spi_bus3, dev, devid, selected);
}
__EXPORT uint8_t imxrt_lpspi3status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI4)
__EXPORT void imxrt_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
imxrt_spixselect(_spi_bus4, dev, devid, selected);
}
__EXPORT uint8_t imxrt_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
/************************************************************************************
* Name: board_spi_reset
*
* Description:
*
*
************************************************************************************/
__EXPORT void board_spi_reset(int ms, int bus_mask)
{
#ifdef CONFIG_IMXRT_LPSPI1
/* Goal not to back feed the chips on the bus via IO lines */
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
if (px4_spi_buses[bus].bus == 1 || px4_spi_buses[bus].bus == 3) {
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
imxrt_config_gpio(_PIN_OFF(px4_spi_buses[bus].devices[i].cs_gpio));
}
if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) {
imxrt_config_gpio(_PIN_OFF(px4_spi_buses[bus].devices[i].drdy_gpio));
}
}
}
}
imxrt_config_gpio(GPIO_SPI1_SCK_OFF);
imxrt_config_gpio(GPIO_SPI1_MISO_OFF);
imxrt_config_gpio(GPIO_SPI1_MOSI_OFF);
imxrt_config_gpio(GPIO_SPI3_SCK_OFF);
imxrt_config_gpio(GPIO_SPI3_MISO_OFF);
imxrt_config_gpio(GPIO_SPI3_MOSI_OFF);
imxrt_config_gpio(_PIN_OFF(GPIO_LPI2C3_SDA_RESET));
imxrt_config_gpio(_PIN_OFF(GPIO_LPI2C3_SCL_RESET));
/* set the sensor rail off */
imxrt_gpio_write(GPIO_VDD_3V3_SENSORS_EN, 0);
/* wait for the sensor rail to reach GND */
usleep(ms * 1000);
warnx("reset done, %d ms", ms);
/* re-enable power */
/* switch the sensor rail back on */
imxrt_gpio_write(GPIO_VDD_3V3_SENSORS_EN, 1);
/* wait a bit before starting SPI, different times didn't influence results */
usleep(100);
/* reconfigure the SPI pins */
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
if (px4_spi_buses[bus].bus == 1 || px4_spi_buses[bus].bus == 3) {
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
imxrt_config_gpio(px4_spi_buses[bus].devices[i].cs_gpio);
}
if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) {
imxrt_config_gpio(px4_spi_buses[bus].devices[i].drdy_gpio);
}
}
}
}
imxrt_config_gpio(GPIO_LPSPI1_SCK);
imxrt_config_gpio(GPIO_LPSPI1_MISO);
imxrt_config_gpio(GPIO_LPSPI1_MOSI);
imxrt_config_gpio(GPIO_LPSPI3_SCK);
imxrt_config_gpio(GPIO_LPSPI3_MISO);
imxrt_config_gpio(GPIO_LPSPI3_MOSI);
imxrt_config_gpio(GPIO_LPI2C3_SDA);
imxrt_config_gpio(GPIO_LPI2C3_SCL);
#endif /* CONFIG_IMXRT_LPSPI1 */
}
#endif /* CONFIG_IMXRT_LPSPI1 || CONFIG_IMXRT_LPSPI2 || CONFIG_IMXRT_LPSPI3 || CONFIG_IMXRT_LPSPI4 */
@@ -58,7 +58,7 @@
/* QTimer3 register accessors */
#define REG(_reg) _REG(IMXRT_TMR3_BASE + IMXRT_TMR_OFFSET(IMXRT_TMR_CH0,(_reg)))
#define REG(_reg) _REG(IMXRT_QTIMER3_BASE + IMXRT_TMR_OFFSET(IMXRT_TMR_CH0,(_reg)))
#define rCOMP1 REG(IMXRT_TMR_COMP1_OFFSET)
#define rCOMP2 REG(IMXRT_TMR_COMP2_OFFSET)
@@ -75,52 +75,28 @@
#define rDMA REG(IMXRT_TMR_DMA_OFFSET)
#define rENBL REG(IMXRT_TMR_ENBL_OFFSET)
// GPIO_EMC_B1_23 FMU_CH1 FLEXPWM1_PWM0_A
// GPIO_EMC_B1_25 FMU_CH2 FLEXPWM1_PWM1_A + FLEXIO1_IO25
// GPIO_EMC_B1_27 FMU_CH3 FLEXPWM1_PWM2_A + FLEXIO1_IO27
// GPIO_EMC_B1_06 FMU_CH4 FLEXPWM2_PWM0_A + FLEXIO1_IO06
// GPIO_EMC_B1_08 FMU_CH5 FLEXPWM2_PWM1_A + FLEXIO1_IO08
// GPIO_EMC_B1_10 FMU_CH6 FLEXPWM2_PWM2_A + FLEXIO1_IO10
// GPIO_EMC_B1_19 FMU_CH7 FLEXPWM2_PWM3_A + FLEXIO1_IO19
// GPIO_EMC_B1_29 FMU_CH8 FLEXPWM3_PWM0_A + FLEXIO1_IO29
// GPIO_EMC_B1_31 FMU_CH9 FLEXPWM3_PWM1_A + FLEXIO1_IO31
// GPIO_EMC_B1_21 FMU_CH10 FLEXPWM3_PWM3_A + FLEXIO1_IO21
// GPIO_EMC_B1_00 FMU_CH11 FLEXPWM4_PWM0_A + FLEXIO1_IO00
// GPIO_EMC_B1_02 FMU_CH12 FLEXPWM4_PWM1_A + FLEXIO1_IO02
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOPWM(PWM::FlexPWM1, PWM::Submodule0),
initIOPWM(PWM::FlexPWM1, PWM::Submodule1),
initIOPWM(PWM::FlexPWM1, PWM::Submodule2),
initIOPWM(PWM::FlexPWM2, PWM::Submodule0),
initIOPWM(PWM::FlexPWM2, PWM::Submodule1),
initIOPWM(PWM::FlexPWM2, PWM::Submodule2),
initIOPWM(PWM::FlexPWM2, PWM::Submodule3),
initIOPWM(PWM::FlexPWM3, PWM::Submodule2),
initIOPWM(PWM::FlexPWM3, PWM::Submodule0),
initIOPWM(PWM::FlexPWM3, PWM::Submodule1),
initIOPWM(PWM::FlexPWM3, PWM::Submodule3),
initIOPWM(PWM::FlexPWM4, PWM::Submodule2),
initIOPWM(PWM::FlexPWM4, PWM::Submodule0),
initIOPWM(PWM::FlexPWM4, PWM::Submodule1),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
/* FMU_CH1 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23),
/* FMU_CH2 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25),
/* FMU_CH3 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27),
/* FMU_CH4 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06),
/* FMU_CH5 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08),
/* FMU_CH6 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10),
/* FMU_CH7 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19),
/* FMU_CH8 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29),
/* FMU_CH9 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_31),
/* FMU_CH10 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_21),
/* FMU_CH11 */ initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_00),
/* FMU_CH12 */ initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_02),
initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06),
initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08),
initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_10),
initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_AD_B0_09),
initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_33),
initIOTimerChannel(io_timers, {PWM::PWM3_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_30),
initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04),
initIOTimerChannel(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_01),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);
@@ -131,18 +107,17 @@ constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
};
void fmuv6xrt_timer_initialize(void)
void fmurt1062_timer_initialize(void)
{
/* We must configure Qtimer 3 as the bus_clk_root which is
* BUS_CLK_ROOT_SYS_PLL3_CLK / 2 = 240 Mhz
* devided by 15 by to yield 16 Mhz
* and deliver that clock to the eFlexPWM1,2,34 via XBAR
/* We must configure Qtimer 3 as the IPG divide by to yield 16 Mhz
* and deliver that clock to the eFlexPWM234 via XBAR
*
* IPG = 240 Mhz
* 16Mhz = 240 / 15
* COMP 1 = 8, COMP2 = 7
* IPG = 144 Mhz
* 16Mhz = 144 / 9
* COMP 1 = 5, COMP2 = 4
*
* */
/* Enable Block Clocks for Qtimer and XBAR1 */
imxrt_clockall_timer3();
@@ -151,8 +126,8 @@ void fmuv6xrt_timer_initialize(void)
/* Disable Timer */
rCTRL = 0;
rCOMP1 = 8 - 1; // N - 1
rCOMP2 = 7 - 1;
rCOMP1 = 5 - 1; // N - 1
rCOMP2 = 4 - 1;
rCAPT = 0;
rLOAD = 0;
@@ -173,9 +148,7 @@ void fmuv6xrt_timer_initialize(void)
*/
rCTRL = (TMR_CTRL_CM_MODE1 | TMR_CTRL_PCS_DIV1 | TMR_CTRL_LENGTH | TMR_CTRL_OUTMODE_TOG_ALT);
/* QTIMER3_TIMER0 -> Flexpwm1,2,34ExtClk */
/* QTIMER3_TIMER0 -> Flexpwm234ExtClk */
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM1_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM2_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM34_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM234_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
}
@@ -121,11 +121,9 @@ void imxrt_usbsuspend(FAR struct usbdev_s *dev, bool resume)
* Returns - 0 if connected.
*
************************************************************************************/
#undef IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT
#define USB1_VBUS_DET_STAT_OFFSET 0xd0
#define IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT (IMXRT_USBPHY1_BASE + USB1_VBUS_DET_STAT_OFFSET)
int board_read_VBUS_state(void)
{
return (getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_3V_VALID) ? 0 : 1;
return (getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) ? 0 : 1;
}
+2 -9
View File
@@ -1,24 +1,18 @@
# CONFIG_BOARD_ROMFSROOT is not set
CONFIG_DRIVERS_BAROMETER_BMP388=n
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=n
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_COMMON_BAROMETERS=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_UAVCAN=y
@@ -53,7 +47,6 @@ CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
+3 -3
View File
@@ -109,10 +109,10 @@ const struct clock_configuration_s g_initial_clkconfig = {
.spll =
{
.mode = SCG_SPLL_MONITOR_DISABLE, /* SPLLCM */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_2, /* SPLLDIV1 160 / 2 = 80Mhz */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_4, /* SPLLDIV2 160 / 4 = 40Mhz */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_2, /* SPLLDIV2 */
.prediv = 1, /* PREDIV */
.mult = 40, /* MULT 8 / 1 * 40 / 2 = 160Mhz */
.mult = 40, /* MULT */
.src = 0, /* SOURCE */
.initialize = true, /* Initialize */
.locked = false, /* LK */
+2 -3
View File
@@ -33,7 +33,7 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
@@ -70,14 +70,12 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -86,6 +84,7 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
+2 -3
View File
@@ -31,7 +31,7 @@ CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
@@ -72,18 +72,17 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
+1 -3
View File
@@ -12,11 +12,9 @@ param set-default MAV_2_RATE 100000
param set-default MAV_2_REMOTE_PRT 14550
param set-default MAV_2_UDP_PRT 14550
# By disabling all 3 INA modules, we use the
# i2c_launcher instead.
param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 0
param set-default SENS_EN_INA226 1
if ver hwtypecmp V6X009010 V6X010010
then
-18
View File
@@ -3,7 +3,6 @@
# PX4 FMUv6X specific board sensors init
#------------------------------------------------------------------------------
set HAVE_PM2 yes
set INA_CONFIGURED no
if ver hwtypecmp V6X005000 V6X005001 V6X005003 V6X005004
then
@@ -26,8 +25,6 @@ then
then
ina226 -X -b 2 -t 2 -k start
fi
set INA_CONFIGURED yes
fi
if param compare SENS_EN_INA228 1
@@ -38,8 +35,6 @@ then
then
ina228 -X -b 2 -t 2 -k start
fi
set INA_CONFIGURED yes
fi
if param compare SENS_EN_INA238 1
@@ -50,24 +45,12 @@ then
then
ina238 -X -b 2 -t 2 -k start
fi
set INA_CONFIGURED yes
fi
#Start Auterion Power Module selector for Skynode boards
if ver hwtypecmp V6X009010 V6X010010
then
pm_selector_auterion start
else
if [ $INA_CONFIGURED = no ]
then
# INA226, INA228, INA238 auto-start
i2c_launcher start -b 1
if [ $HAVE_PM2 = yes ]
then
i2c_launcher start -b 2
fi
fi
fi
if ver hwtypecmp V6X000006 V6X004006 V6X005006
@@ -161,5 +144,4 @@ fi
# Baro on I2C3
ms5611 -X start
unset INA_CONFIGURED
unset HAVE_PM2
@@ -207,6 +207,7 @@ CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDMMC2_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
@@ -286,7 +287,6 @@ CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_DHCPC_RENEW=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_PING=y
CONFIG_SYSTEM_SYSTEM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
-3
View File
@@ -1,3 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""
Binary file not shown.
@@ -1,28 +0,0 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
# Mavlink ethernet (CFG 1000)
param set-default MAV_2_CONFIG 1000
param set-default MAV_2_BROADCAST 1
param set-default MAV_2_MODE 0
param set-default MAV_2_RADIO_CTL 0
param set-default MAV_2_RATE 100000
param set-default MAV_2_REMOTE_PRT 14550
param set-default MAV_2_UDP_PRT 14550
param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1
param set-default SYS_USE_IO 1
safety_button start
if param greater -s UAVCAN_ENABLE 0
then
ifup can0
ifup can1
ifup can2
fi
@@ -1,13 +0,0 @@
#!/bin/sh
#
# PX4 FMUv6X-RT specific board MAVLink startup script.
#------------------------------------------------------------------------------
# if skynode base board is detected start Mavlink on Telem2
if ver hwtypecmp V6XRT009000 V6XRT010000
then
mavlink start -d /dev/ttyS5 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
# Ensure nothing else starts on TEL2 (ttyS5)
set PRT_TEL2_ 1
fi
@@ -1,89 +0,0 @@
#!/bin/sh
#
# PX4 FMUv5 specific board sensors init
#------------------------------------------------------------------------------
#
# UART mapping on PX4 FMU-V6XRT:
#
# LPUART1 /dev/ttyS0 CONSOLE
# LPUART3 /dev/ttyS1 GPS
# LPUART4 /dev/ttyS2 TELEM1
# LPUART5 /dev/ttyS4 GPS2
# LPUART6 /dev/ttyS5 PX4IO
# LPUART8 /dev/ttyS6 TELEM2
# LPUART10 /dev/ttyS7 TELEM3
# LPUART11 /dev/ttyS8 EXT2
#
#------------------------------------------------------------------------------
set HAVE_PM2 yes
if ver hwtypecmp V5X005000 V5X005001 V5X005002
then
set HAVE_PM2 no
fi
if param compare -s ADC_ADS1115_EN 1
then
ads1115 start -X
else
board_adc start
fi
if param compare SENS_EN_INA226 1
then
# Start Digital power monitors
ina226 -X -b 1 -t 1 -k start
if [ $HAVE_PM2 = yes ]
then
ina226 -X -b 2 -t 2 -k start
fi
fi
if param compare SENS_EN_INA228 1
then
# Start Digital power monitors
ina228 -X -b 1 -t 1 -k start
if [ $HAVE_PM2 = yes ]
then
ina228 -X -b 2 -t 2 -k start
fi
fi
if param compare SENS_EN_INA238 1
then
# Start Digital power monitors
ina238 -X -b 1 -t 1 -k start
if [ $HAVE_PM2 = yes ]
then
ina238 -X -b 2 -t 2 -k start
fi
fi
# Internal SPI bus ICM42688p (hard-mounted)
icm42688p -R 12 -b 1 -s start
# Internal on IMU SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Internal on IMU SPI bus ICM42688p
icm42688p -R 6 -b 2 -s start
# Internal magnetometer on I2c
bmm150 -I start
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
ist8310 -X -b 1 -R 10 start
# Possible internal Baro
# Disable startup of internal baros if param is set to false
if param compare SENS_INT_BARO_EN 1
then
bmp388 -I -b 3 -a 0x77 start
bmp388 -X -b 2 start
fi
unset HAVE_PM2
@@ -1,110 +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_DEV_CONSOLE is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_SPI_EXCHANGE is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/px4/fmu-v6xrt/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="imxrt"
CONFIG_ARCH_CHIP_IMXRT=y
CONFIG_ARCH_CHIP_MIMXRT1176DVMAA=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_RAMVECTORS=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_ITCM=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU=y
CONFIG_BOARDCTL=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_BOOTLOADER_FIXUP=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_FORCE_ALIGNMENT=y
CONFIG_BOARD_INITTHREAD_PRIORITY=254
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=104926
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_CDCACM=y
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x001d
CONFIG_CDCACM_PRODUCTSTR="PX4 BL FMU v6XRT.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3643
CONFIG_CDCACM_VENDORSTR="Dronecode Project, Inc."
CONFIG_DEBUG_ASSERTIONS=y
CONFIG_DEBUG_ERROR=y
CONFIG_DEBUG_FEATURES=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEBUG_USAGEFAULT=y
CONFIG_DEFAULT_SMALL=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_IMXRT_EDMA=y
CONFIG_IMXRT_EDMA_EDBG=y
CONFIG_IMXRT_EDMA_ELINK=y
CONFIG_IMXRT_EDMA_NTCD=64
CONFIG_IMXRT_FLEXSPI2=y
CONFIG_IMXRT_LPUART8=y
CONFIG_IMXRT_SNVS_LPSRTC=y
CONFIG_IMXRT_USBDEV=y
CONFIG_INIT_ENTRYPOINT="bootloader_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LPUART8_BAUD=57600
CONFIG_LPUART8_IFLOWCONTROL=y
CONFIG_LPUART8_OFLOWCONTROL=y
CONFIG_LPUART8_RXBUFSIZE=600
CONFIG_LPUART8_RXDMA=y
CONFIG_LPUART8_TXBUFSIZE=1500
CONFIG_LPUART8_TXDMA=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=1835008
CONFIG_RAM_START=0x20240000
CONFIG_RAW_BINARY=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_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_SYSTEMTICK_HOOK=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_DMA=y
CONFIG_USBDEV_DUALSPEED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
@@ -1,355 +0,0 @@
/************************************************************************************
* nuttx-configs/px4/fmu-v6xrt/include/board.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_PX4_FMU_V6XRT_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_PX4_FMU_V6XRT_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
#define BOARD_CPU_FREQUENCY 996000000 //FIXME
#define IMXRT_IPG_PODF_DIVIDER 5
#define BOARD_GPT_FREQUENCY 24000000
#define BOARD_XTAL_FREQUENCY 24000000
/* SDIO *********************************************************************/
/* Pin drive characteristics - drive strength in particular may need tuning
* for specific boards.
*/
#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | IOMUX_USDHC1_DATAX_DEFAULT) /* GPIO_SD_B1_02 */
#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | IOMUX_USDHC1_DATAX_DEFAULT) /* GPIO_SD_B1_03 */
#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | IOMUX_USDHC1_DATAX_DEFAULT) /* GPIO_SD_B1_04 */
#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | IOMUX_USDHC1_DATAX_DEFAULT) /* GPIO_SD_B1_05 */
#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | IOMUX_USDHC1_CLK_DEFAULT) /* GPIO_SD_B1_01 */
#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | IOMUX_USDHC1_CMD_DEFAULT) /* GPIO_SD_B1_00 */
#define PIN_USDHC1_CD (GPIO_USDHC1_CD_2 | IOMUX_USDHC1_CLK_DEFAULT) /* GPIO_AD_32 */
/* 386 KHz for initial inquiry stuff */
#define BOARD_USDHC_IDMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV256
#define BOARD_USDHC_IDMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(2)
/* 24.8MHz for other modes */
#define BOARD_USDHC_MMCMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_MMCMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD1MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD1MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD4MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD4MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
/* LED definitions ******************************************************************/
/* The px4 fmu-v6x board has numerous LEDs but only three, LED_GREEN a Green LED,
* LED_BLUE a Blue LED and LED_RED a Red LED, that can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* PIO Disambiguation ***************************************************************/
/* LPUARTs
*
* We pull down CTS so that if nothing is connected, conde will not block.
*/
#define IOMUX_UART_CTS_DEFAULT (IOMUX_PULL_DOWN | IOMUX_DRIVE_HIGHSTRENGTH | IOMUX_SLEW_SLOW)
#define IOMUX_UART_BOARD_DEFAULT (IOMUX_PULL_NONE | IOMUX_DRIVE_HIGHSTRENGTH | IOMUX_SLEW_FAST)
/* Debug */
#define GPIO_LPUART1_RX (GPIO_LPUART1_RX_2|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART1_RX_DEBUG GPIO_DISP_B1_03 */
#define GPIO_LPUART1_TX (GPIO_LPUART1_TX_2|IOMUX_UART_BOARD_DEFAULT) /* UART1_TX_DEBUG GPIO_DISP_B1_02 */
/* GPS 1 */
#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_1|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART3_RX_GPS1 GPIO_AD_31 */
#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_1|IOMUX_UART_DEFAULT) /* UART3_TX_GPS1 GPIO_AD_30 */
/* Telem 1 */
#define GPIO_LPUART4_CTS (GPIO_LPUART4_CTS_1|IOMUX_UART_CTS_DEFAULT|PADMUX_SION) /* UART4_CTS_TELEM1 GPIO_DISP_B1_05 */
#define GPIO_LPUART4_RTS (GPIO_PORT4 | GPIO_PIN28 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* UART4_RTS_TELEM1 GPIO_DISP_B1_07 GPIO4 Pin 28 */
#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_1|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART4_RX_TELEM1 GPIO_DISP_B1_04 */
#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_1|IOMUX_UART_BOARD_DEFAULT) /* UART4_TX_TELEM1 GPIO_DISP_B1_06 */
/* GPS 2 */
#define GPIO_LPUART5_RX (GPIO_LPUART5_RX_1|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART5_RX_GPS2 GPIO_AD_29 */
#define GPIO_LPUART5_TX (GPIO_LPUART5_TX_1|IOMUX_UART_DEFAULT) /* UART5_TX_GPS2 GPIO_AD_28 */
/* PX4IO */
#define GPIO_LPUART6_RX (GPIO_LPUART6_RX_1|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART6_RX_FROM_IO__NC GPIO_EMC_B1_41 */
#define GPIO_LPUART6_TX (GPIO_LPUART6_TX_1|IOMUX_UART_DEFAULT) /* UART6_TX_TO_IO__RC_INPUT GPIO_EMC_B1_40 */
/* Telem 2 */
#define GPIO_LPUART8_CTS (GPIO_LPUART8_CTS_1|IOMUX_UART_CTS_DEFAULT|PADMUX_SION) /* UART8_CTS_TELEM2 GPIO_AD_04 */
#define GPIO_LPUART8_RTS (GPIO_PORT3 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* UART8_RTS_TELEM2 GPIO_AD_05 GPIO3 Pin 4 */
#define GPIO_LPUART8_RX (GPIO_LPUART8_RX_2|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART8_RX_TELEM2 GPIO_AD_03 */
#define GPIO_LPUART8_TX (GPIO_LPUART8_TX_2|IOMUX_UART_BOARD_DEFAULT) /* UART8_TX_TELEM2 GPIO_AD_02 */
/* Telem 3 */
#define GPIO_LPUART10_CTS (GPIO_LPUART10_CTS_1|IOMUX_UART_CTS_DEFAULT|PADMUX_SION) /* UART10_CTS_TELEM3 GPIO_AD_34 */
#define GPIO_LPUART10_RTS (GPIO_PORT4 | GPIO_PIN2 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* UART10_RTS_TELEM3 GPIO_AD_35 GPIO4 Pin 2 */
#define GPIO_LPUART10_RX (GPIO_LPUART10_RX_2|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART10_RX_TELEM3 GPIO_AD_33 */
#define GPIO_LPUART10_TX (GPIO_LPUART10_TX_1|IOMUX_UART_BOARD_DEFAULT) /* UART10_TX_TELEM3 GPIO_AD_15 */
/* Ext 2 */
/* No DMA Support at this time for lack of DMA1, DMAMUX1 support */
#define GPIO_LPUART11_RX (GPIO_LPUART11_RX_2|IOMUX_UART_DEFAULT|PADMUX_SION) /* UART11_RX_EXTERNAL2 GPIO_LPSR_05 */
#define GPIO_LPUART11_TX (GPIO_LPUART11_TX_2|IOMUX_UART_DEFAULT) /* UART11_TX_EXTERNAL2 GPIO_LPSR_04 */
/* CAN
*
* CAN1 is routed to transceiver.
* CAN2 is routed to transceiver.
* CAN3 is routed to transceiver.
*/
#define FLEXCAN_IOMUX (IOMUX_PULL_UP | IOMUX_SLEW_FAST)
#define GPIO_FLEXCAN1_TX (GPIO_FLEXCAN1_TX_1 | FLEXCAN_IOMUX) /* GPIO_AD_06 */
#define GPIO_FLEXCAN1_RX (GPIO_FLEXCAN1_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_07 */
#define GPIO_FLEXCAN2_TX (GPIO_FLEXCAN2_TX_1 | FLEXCAN_IOMUX) /* GPIO_AD_00 */
#define GPIO_FLEXCAN2_RX (GPIO_FLEXCAN2_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_01 */
#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_1 | FLEXCAN_IOMUX) /* GPIO_LPSR_00 */
#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_1 | FLEXCAN_IOMUX) /* GPIO_LPSR_01 */
/* LPSPI */
#define GPIO_LPSPI1_MISO (GPIO_LPSPI1_SDI_2|IOMUX_LPSPI_DEFAULT) /* SPI1_MISO_SENSOR1 GPIO_EMC_B2_03 */
#define GPIO_LPSPI1_MOSI (GPIO_LPSPI1_SDO_2|IOMUX_LPSPI_DEFAULT) /* SPI1_MOSI_SENSOR1 GPIO_EMC_B2_02 */
#define GPIO_LPSPI1_SCK (GPIO_LPSPI1_SCK_2|IOMUX_LPSPI_DEFAULT) /* SPI1_SCK_SENSOR1 GPIO_EMC_B2_00 */
#define GPIO_LPSPI2_MISO (GPIO_LPSPI2_SDI_1|IOMUX_LPSPI_DEFAULT) /* SPI2_MISO_SENSOR2 GPIO_AD_27 */
#define GPIO_LPSPI2_MOSI (GPIO_LPSPI2_SDO_1|IOMUX_LPSPI_DEFAULT) /* SPI2_MOSI_SENSOR2 GPIO_AD_26 */
#define GPIO_LPSPI2_SCK (GPIO_LPSPI2_SCK_1|IOMUX_LPSPI_DEFAULT) /* SPI2_SCK_SENSOR2 GPIO_AD_24 */
#define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_1|IOMUX_LPSPI_DEFAULT) /* SPI3_MISO_SENSOR3 GPIO_EMC_B2_07 */
#define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_1|IOMUX_LPSPI_DEFAULT) /* SPI3_MOSI_SENSOR3 GPIO_EMC_B2_06 */
#define GPIO_LPSPI3_SCK (GPIO_LPSPI3_SCK_1|IOMUX_LPSPI_DEFAULT) /* SPI3_SCK_SENSOR3 GPIO_EMC_B2_04 */
/* SPI4 Not connected to anything */
//#define GPIO_LPSPI4_MISO (GPIO_LPSPI4_SDI_2|IOMUX_LPSPI_DEFAULT) /* SPI4_MISO_SENSOR4 GPIO_DISP_B2_13 */
//#define GPIO_LPSPI4_MOSI (GPIO_LPSPI4_SDO_2|IOMUX_LPSPI_DEFAULT) /* SPI4_MOSI_SENSOR4 GPIO_DISP_B2_14 */
//#define GPIO_LPSPI4_SCK (GPIO_LPSPI4_SCK_2|IOMUX_LPSPI_DEFAULT) /* SPI4_SCK_SENSOR4 GPIO_DISP_B2_12 */
/* LPSPI6 No DMA Support at this time for lack of DMA1, DMAMUX1 support */
#define GPIO_LPSPI6_MISO (GPIO_LPSPI6_SDI_1|IOMUX_LPSPI_DEFAULT) /* SPI6_MISO_EXTERNAL1 GPIO_LPSR_12 */
#define GPIO_LPSPI6_MOSI (GPIO_LPSPI6_SDO_1|IOMUX_LPSPI_DEFAULT) /* SPI6_MOSI_EXTERNAL1 GPIO_LPSR_11 */
#define GPIO_LPSPI6_SCK (GPIO_LPSPI6_SCK_1|IOMUX_LPSPI_DEFAULT) /* SPI6_SCK_EXTERNAL1 GPIO_LPSR_10 */
/* LPI2Cs */
#define GPIO_LPI2C1_SCL_RESET (GPIO_PORT3 | GPIO_PIN7 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C1_SCL_GPS1 GPIO_AD_08 GPIO_GPIO3_IO07 */
#define GPIO_LPI2C1_SDA_RESET (GPIO_PORT3 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C1_SDA_GPS1 GPIO_AD_09 GPIO_GPIO3_IO08 */
#define GPIO_LPI2C1_SCL (GPIO_LPI2C1_SCL_2|IOMUX_LPI2C_DEFAULT) /* I2C1_SCL_GPS1 GPIO_AD_08 */
#define GPIO_LPI2C1_SDA (GPIO_LPI2C1_SDA_2|IOMUX_LPI2C_DEFAULT) /* I2C1_SDA_GPS1 GPIO_AD_09 */
#define GPIO_LPI2C2_SCL_RESET (GPIO_PORT3 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C2_SCL_GPS2 GPIO_AD_18 GPIO_GPIO3_IO17 */
#define GPIO_LPI2C2_SDA_RESET (GPIO_PORT3 | GPIO_PIN18 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C2_SDA_GPS2 GPIO_AD_19 GPIO_GPIO3_IO18 */
#define GPIO_LPI2C2_SCL (GPIO_LPI2C2_SCL_2|IOMUX_LPI2C_DEFAULT) /* I2C2_SCL_GPS2 GPIO_AD_18 */
#define GPIO_LPI2C2_SDA (GPIO_LPI2C2_SDA_2|IOMUX_LPI2C_DEFAULT) /* I2C2_SDA_GPS2 GPIO_AD_19 */
#define GPIO_LPI2C3_SCL_RESET (GPIO_PORT5 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C3_SCL_FMU GPIO_DISP_B2_10 GPIO_GPIO5_IO11_1 */
#define GPIO_LPI2C3_SDA_RESET (GPIO_PORT5 | GPIO_PIN12 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C3_SDA_FMU GPIO_DISP_B2_11 GPIO_GPIO5_IO12_1 */
#define GPIO_LPI2C3_SCL (GPIO_LPI2C3_SCL_2|IOMUX_LPI2C_DEFAULT) /* I2C3_SCL_FMU GPIO_DISP_B2_10 */
#define GPIO_LPI2C3_SDA (GPIO_LPI2C3_SDA_2|IOMUX_LPI2C_DEFAULT) /* I2C3_SDA_FMU GPIO_DISP_B2_11 */
#define GPIO_LPI2C6_SCL_RESET (GPIO_PORT6 | GPIO_PIN7 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C6_SCL_EXTERNAL2 GPIO_LPSR_07 GPIO_GPIO6_IO07_1 */
#define GPIO_LPI2C6_SDA_RESET (GPIO_PORT6 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE) /* I2C6_SDA_EXTERNAL2 GPIO_LPSR_06 GPIO_GPIO6_IO06_1 */
/* LPI2C6 No DMA Support at this time for lack of DMA1, DMAMUX1 support */
#define GPIO_LPI2C6_SCL (GPIO_LPI2C6_SCL_1|IOMUX_LPI2C_DEFAULT) /* I2C6_SCL_EXTERNAL2 GPIO_LPSR_07 */
#define GPIO_LPI2C6_SDA (GPIO_LPI2C6_SDA_1|IOMUX_LPI2C_DEFAULT) /* I2C6_SDA_EXTERNAL2 GPIO_LPSR_06 */
/* ETH Disambiguation *******************************************************/
// This is the ENET_1G interface.
#if defined(CONFIG_ETH0_PHY_TJA1103)
# define BOARD_PHY_ADDR (18)
#endif
#if defined(CONFIG_ETH0_PHY_LAN8742A)
# define BOARD_PHY_ADDR (0)
#endif
#define GPIO_ENET2_TX_DATA00 (GPIO_ENET_1G_TX_DATA0_1|IOMUX_ENET_DATA_DEFAULT) /* GPIO_DISP_B1_09 */
#define GPIO_ENET2_TX_DATA01 (GPIO_ENET_1G_TX_DATA1_1|IOMUX_ENET_DATA_DEFAULT) /* GPIO_DISP_B1_08 */
#define GPIO_ENET2_RX_DATA00 (GPIO_ENET_1G_RX_DATA0_2|IOMUX_ENET_DATA_DEFAULT) /* GPIO_EMC_B2_15 */
#define GPIO_ENET2_RX_DATA01 (GPIO_ENET_1G_RX_DATA1_2|IOMUX_ENET_DATA_DEFAULT) /* GPIO_EMC_B2_16 */
#define GPIO_ENET2_MDIO (GPIO_ENET_1G_MDIO_1|IOMUX_ENET_MDIO_DEFAULT) /* GPIO_EMC_B2_20 */
#define GPIO_ENET2_MDC (GPIO_ENET_1G_MDC_1|IOMUX_ENET_MDC_DEFAULT) /* GPIO_EMC_B2_19 */
#define GPIO_ENET2_RX_EN (GPIO_ENET_1G_RX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_DISP_B1_00 */
#define GPIO_ENET2_RX_ER (GPIO_ENET_RX_ER_1|IOMUX_ENET_RXERR_DEFAULT) /* GPIO_DISP_B1_01 */
#define GPIO_ENET2_TX_CLK (GPIO_ENET_1G_REF_CLK_1|IOMUX_ENET_TX_CLK_DEFAULT) /* GPIO_DISP_B1_11 */
#define GPIO_ENET2_TX_EN (GPIO_ENET_1G_TX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_DISP_B1_10 */
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
#include <imxrt_gpio.h>
#include <imxrt_iomuxc.h>
// add -I<full path> build/px4_fmu-v6xrt_default/NuttX/nuttx/arch/arm/src/chip \ to NuttX Makedefs.in
#define PROBE_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE)
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 /* GPIO_B0_06 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_2 /* GPIO_EMC_08 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_3 /* GPIO_EMC_10 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_4 /* GPIO_AD_B0_09 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_5 /* GPIO_EMC_33 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_6 /* GPIO_EMC_30 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_7 /* GPIO_EMC_04 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_8 /* GPIO_EMC_01 */ (GPIO_PORT4 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { imxrt_config_gpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { imxrt_config_gpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { imxrt_config_gpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { imxrt_config_gpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { imxrt_config_gpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { imxrt_config_gpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { imxrt_config_gpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { imxrt_config_gpio(PROBE_8); } \
} while(0)
# define PROBE(n,s) do {imxrt_gpio_write(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __NUTTX_CONFIG_PX4_FMU_V6XRT_INCLUDE_BOARD_H */
@@ -1,195 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/nuttx-config/scripts/bootloader_script.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/* Specify the memory areas */
/* Reallocate
* Final Configuration is
* No DTCM
* 512k OCRAM M7 (FlexRAM) (2038:0000-203f:ffff)
* 128k OCRAMM7 FlexRAM ECC (2036:0000-2037:ffff)
* 64k OCRAM2 ECC parity (2035:0000-2035:ffff)
* 64k OCRAM1 ECC parity (2034:0000-2034:ffff)
* 512k FlexRAM OCRAM2 (202C:0000-2033:ffff)
* 512k FlexRAM OCRAM1 (2024:0000-202B:ffff)
* 256k System OCRAM M4 (2020:0000-2023:ffff)
*/
MEMORY
{
flash (rx) : ORIGIN = 0x30000000, LENGTH = 128K
sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k-512k
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 256K /* TODO FlexRAM partition */
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 256K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
EXTERN(g_flash_config)
EXTERN(g_image_vector_table)
EXTERN(g_boot_data)
EXTERN(board_get_manifest)
EXTERN(_bootdelay_signature)
ENTRY(__start)
SECTIONS
{
/* Image Vector Table and Boot Data for booting from external flash */
.boot_hdr : ALIGN(4)
{
FILL(0xff)
. = 0x400 ;
__boot_hdr_start__ = ABSOLUTE(.) ;
KEEP(*(.boot_hdr.conf))
. = 0x1000 ;
KEEP(*(.boot_hdr.ivt))
. = 0x1020 ;
KEEP(*(.boot_hdr.boot_data))
. = 0x1030 ;
KEEP(*(.boot_hdr.dcd_data))
__boot_hdr_end__ = ABSOLUTE(.) ;
. = 0x2000 ;
} >flash
.vectors :
{
KEEP(*(.vectors))
*(.text .text.__start)
} >flash
.itcmfunc :
{
. = ALIGN(8);
_sitcmfuncs = ABSOLUTE(.);
FILL(0xFF)
. = 0x40 ;
. = ALIGN(8);
_eitcmfuncs = ABSOLUTE(.);
} > itcm AT > flash
_fitcmfuncs = LOADADDR(.itcmfunc);
/* The RAM vector table (if present) should lie at the beginning of SRAM */
.ram_vectors (COPY) : {
*(.ram_vectors)
} > dtcm
.text : ALIGN(4)
{
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
. = ALIGN(4096);
_etext = ABSOLUTE(.);
_srodata = ABSOLUTE(.);
*(.rodata .rodata.*)
. = ALIGN(4096);
_erodata = ABSOLUTE(.);
} > flash
.init_section :
{
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab :
{
*(.ARM.extab*)
} > flash
.ARM.exidx :
{
__exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
__exidx_end = ABSOLUTE(.);
} > flash
_eronly = ABSOLUTE(.);
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.ramfunc ALIGN(4):
{
_sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > flash
_framfuncs = LOADADDR(.ramfunc);
.bss :
{
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
_boot_loadaddr = ORIGIN(flash);
_boot_size = LENGTH(flash);
_ram_size = LENGTH(sram);
_sdtcm = ORIGIN(dtcm);
_edtcm = ORIGIN(dtcm) + LENGTH(dtcm);
}
@@ -1,830 +0,0 @@
*(.text.hrt_absolute_time)
*(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj)
*(.text._ZN13MavlinkStream6updateERKy)
*(.text._ZN7Mavlink16update_rate_multEv)
*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_)
*(.text._ZN13MavlinkStream12get_size_avgEv)
*(.text._ZN16ControlAllocator3RunEv)
*(.text._ZN22MulticopterRateControl3RunEv.part.0)
*(.text._ZN7Mavlink9task_mainEiPPc)
*(.text._ZN7sensors22VehicleAngularVelocity3RunEv)
*(.text.memset)
*(.text._ZN4uORB12Subscription9subscribeEv.part.0)
*(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb)
*(.text._ZN4uORB10DeviceNode5writeEP4filePKcj)
*(.text.exception_common)
*(.text.strcmp)
*(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv)
*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah)
*(.text._Z12get_orb_meta6ORB_ID)
*(.text.nxsem_wait)
*(.text._ZN9ICM42688P12ProcessAccelERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text.nxsem_post)
*(.text._ZN3px49WorkQueue3RunEv)
*(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN4EKF23RunEv)
*(.text.imxrt_lpspi_exchange)
*(.text.imxrt_dmach_xfrsetup)
*(.text.arm_doirq)
*(.text._ZN7sensors10VehicleIMU7PublishEv)
*(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE)
*(.text._ZN7sensors10VehicleIMU10UpdateGyroEv)
*(.text._ZN9ICM42688P8FIFOReadERKyh)
*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE)
*(.text._ZN16PX4Accelerometer10updateFIFOER19sensor_accel_fifo_s)
*(.text.up_block_task)
*(.text._ZN7sensors22VehicleAngularVelocity19CalibrateAndPublishERKyRKN6matrix7Vector3IfEES7_)
*(.text._ZN4uORB12Subscription10advertisedEv)
*(.text._ZNK15AttitudeControl6updateERKN6matrix10QuaternionIfEE)
*(.text._ZN7sensors10VehicleIMU11UpdateAccelEv)
*(.text.perf_set_elapsed.part.0)
*(.text._ZN4uORB12Subscription6updateEPv)
*(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s)
*(.text.hrt_tim_isr)
*(.text.nxsig_timedwait)
*(.text.nxsem_foreachholder)
*(.text._ZN7sensors10VehicleIMU3RunEv)
*(.text.up_unblock_task)
*(.text.__aeabi_l2f)
*(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_)
*(.text.sched_unlock)
*(.text.pthread_mutex_timedlock)
*(.text.nxsem_restore_baseprio)
*(.text._ZN7sensors22VehicleAngularVelocity21FilterAngularVelocityEiPfi)
*(.text._ZN26MulticopterAttitudeControl3RunEv.part.0)
*(.text._ZN6device3SPI9_transferEPhS1_j)
*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f)
*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s)
*(.text._Z9rotate_3i8RotationRsS0_S0_)
*(.text.fs_getfilep)
*(.text.MEM_DataCopy0_1)
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
*(.text.sched_note_resume)
*(.text.uart_ioctl)
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
*(.text.pthread_mutex_take)
*(.text._ZN14ImuDownSampler6updateERKN9estimator9imuSampleE)
*(.text.irq_dispatch)
*(.text._ZN39ControlAllocationSequentialDesaturation6mixYawEv)
*(.text._ZN16ControlAllocator25publish_actuator_controlsEv.part.0)
*(.text._ZN9ICM42688P7RunImplEv)
*(.text._ZN4uORB12Subscription9subscribeEv)
*(.text.param_get)
*(.text._do_memcpy)
*(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb)
*(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE)
*(.text.wd_start)
*(.text.sq_rem)
*(.text.nxsem_add_holder_tcb)
*(.text.imxrt_dmaterminate)
*(.text.hrt_call_enter)
*(.text._ZN4EKF220PublishLocalPositionERKy)
*(.text._mav_finalize_message_chan_send)
*(.text.nxsched_add_blocked)
*(.text.arm_switchcontext)
*(.text._ZN3Ekf19fixCovarianceErrorsEb)
*(.text.nxsched_add_prioritized)
*(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb)
*(.text.ioctl)
*(.text._ZN6events12SendProtocol6updateERKy)
*(.text.imxrt_dmach_interrupt)
*(.text.sched_lock)
*(.text._ZN6device3SPI8transferEPhS1_j)
*(.text._ZN27MavlinkStreamDistanceSensor4sendEv)
*(.text.hrt_call_internal)
*(.text.arm_svcall)
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
*(.text._ZN7Mavlink15get_free_tx_bufEv)
*(.text.nx_poll)
*(.text.sched_note_suspend)
*(.text._ZN15MavlinkReceiver3runEv)
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_)
*(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE)
*(.text._ZN3px46logger6Logger3runEv)
*(.text.nxsem_freecount0holder)
*(.text._ZN4uORB20SubscriptionInterval7updatedEv)
*(.text._ZN24MavlinkStreamCommandLong4sendEv)
*(.text._ZN9Commander3runEv)
*(.text.nxsem_release_holder)
*(.text._ZN3Ekf17predictCovarianceERKN9estimator9imuSampleE)
*(.text.wd_cancel)
*(.text._ZN7Sensors3RunEv)
*(.text.perf_end)
*(.text._ZN4uORB12Subscription7updatedEv)
*(.text._ZN13land_detector12LandDetector3RunEv)
*(.text.sched_idletask)
*(.text.atanf)
*(.text.uart_write)
*(.text.pthread_mutex_unlock)
*(.text.__ieee754_asinf)
*(.text.MEM_DataCopy0_2)
*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t)
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
*(.text.__ieee754_atan2f)
*(.text._ZNK18DynamicSparseLayer3getEt)
*(.text.nxsched_remove_readytorun)
*(.text.__udivmoddi4)
*(.text._ZN8Failsafe17checkStateAndModeERKyRKN12FailsafeBase5StateERK16failsafe_flags_s)
*(.text._ZN29MavlinkStreamHygrometerSensor4sendEv)
*(.text.nxsched_remove_blocked)
*(.text.pthread_mutex_give)
*(.text._ZN3Ekf18controlFusionModesERKN9estimator9imuSampleE)
*(.text._ZN4cdev4CDev11poll_notifyEm)
*(.text.file_vioctl)
*(.text.wd_timer)
*(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s)
*(.text.nxsig_nanosleep)
*(.text.imxrt_lpspi1select)
*(.text.sem_wait)
*(.text.perf_count_interval.part.0)
*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason)
*(.text.MEM_LongCopyJump)
*(.text.px4_arch_adc_sample)
*(.text._ZN31MulticopterHoverThrustEstimator3RunEv)
*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE)
*(.text._ZN4uORB7Manager17get_device_masterEv)
*(.text._ZN13DataValidator3putEyPKfmh)
*(.text.cdcuart_ioctl)
*(.text.cdcacm_sndpacket)
*(.text._ZN7sensors22VehicleAngularVelocity16SensorBiasUpdateEb)
*(.text.nxsched_merge_pending)
*(.text._ZN13MavlinkStream11update_dataEv)
*(.text._ZN7sensors18VotedSensorsUpdate21calcGyroInconsistencyEv)
*(.text.param_set_used)
*(.text._ZN18EstimatorInterface10setIMUDataERKN9estimator9imuSampleE)
*(.text._ZN18DataValidatorGroup8get_bestEyPi)
*(.text._ZN4EKF218PublishInnovationsERKy)
*(.text._ZN21MavlinkMissionManager4sendEv)
*(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf)
*(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb)
*(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b)
*(.text._ZN22MavlinkStreamCollision4sendEv)
*(.text.imxrt_lpi2c_transfer)
*(.text.uart_putxmitchar)
*(.text.nxsem_tickwait)
*(.text.clock_nanosleep)
*(.text.memcpy)
*(.text.up_release_pending)
*(.text.MEM_DataCopy0)
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
*(.text.dq_rem)
*(.text._ZN15GyroCalibration3RunEv.part.0)
*(.text.imxrt_edma_interrupt)
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
*(.text.nxsched_process_timer)
*(.text.sinf)
*(.text.hrt_call_after)
*(.text._ZN39ControlAllocationSequentialDesaturation8allocateEv)
*(.text.up_invalidate_dcache)
*(.text._ZN15PositionControl16_velocityControlEf)
*(.text._ZN4EKF222PublishAidSourceStatusERKy)
*(.text._ZN4ListIP13MavlinkStreamE8IteratorppEv)
*(.text._ZN20MavlinkStreamESCInfo4sendEv)
*(.text.sem_post)
*(.text._ZN3px417ScheduledWorkItem15ScheduleDelayedEm)
*(.text.nxsched_resume_scheduler)
*(.text.nxsched_add_readytorun)
*(.text._ZN10FlightTaskC1Ev)
*(.text.usleep)
*(.text._ZN14FlightTaskAutoC1Ev)
*(.text.sem_getvalue)
*(.text._ZN23MavlinkStreamHighresIMU4sendEv)
*(.text.imxrt_gpio_write)
*(.text._ZN3Ekf6updateEv)
*(.text.__ieee754_acosf)
*(.text.nxsem_wait_uninterruptible)
*(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE)
*(.text._ZN9Commander13dataLinkCheckEv)
*(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex)
*(.text._ZNK3Ekf26get_innovation_test_statusERtRfS1_S1_S1_S1_S1_S1_)
*(.text._ZN12PX4Gyroscope9set_scaleEf)
*(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s)
*(.text._ZN18MavlinkStreamDebug4sendEv)
*(.text._ZN27MavlinkStreamServoOutputRawILi0EE4sendEv)
*(.text.asinf)
*(.text.nxsem_freeholder)
*(.text._ZN6matrix5EulerIfEC1ERKNS_3DcmIfEE)
*(.text._ZN4EKF227PublishInnovationTestRatiosERKy)
*(.text.imxrt_gpio3_16_31_interrupt)
*(.text._ZN4EKF213PublishStatusERKy)
*(.text._ZN4EKF226PublishInnovationVariancesERKy)
*(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv)
*(.text.imxrt_dmach_start)
*(.text._ZN3ADC19update_system_powerEy)
*(.text._ZNK3Ekf19get_ekf_soln_statusEPt)
*(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb)
*(.text.imxrt_gpio_read)
*(.text._ZN32MavlinkStreamNavControllerOutput4sendEv)
*(.text._ZN15ArchPX4IOSerial13_bus_exchangeEP8IOPacket)
*(.text._ZN39MavlinkStreamGimbalDeviceAttitudeStatus4sendEv)
*(.text._ZNK10ConstLayer3getEt)
*(.text.__aeabi_uldivmod)
*(.text.up_udelay)
*(.text.imxrt_usbinterrupt)
*(.text.up_idle)
*(.text._ZN20MavlinkStreamGPS2Raw4sendEv)
*(.text._ZN4EKF217UpdateCalibrationERKyRNS_19InFlightCalibrationERKN6matrix7Vector3IfEES8_fbb)
*(.text._ZN28MavlinkStreamGpsGlobalOrigin4sendEv)
*(.text._ZN11ControlMath15bodyzToAttitudeEN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s)
*(.text._ZN4EKF217UpdateRangeSampleER17ekf2_timestamps_s)
*(.text._ZN3Ekf24controlOpticalFlowFusionERKN9estimator9imuSampleE)
*(.text._ZN19MavlinkStreamRawRpm4sendEv)
*(.text._ZN13MavlinkStream10const_rateEv)
*(.text._ZN4EKF215PublishOdometryERKyRKN9estimator9imuSampleE)
*(.text._ZN15FailureDetector20updateAttitudeStatusERK16vehicle_status_s)
*(.text._ZN7Mavlink19configure_sik_radioEv)
*(.text._ZN13BatteryStatus8adc_pollEv)
*(.text.getpid)
*(.text._ZN13DataValidator10confidenceEy)
*(.text._ZN22MavlinkStreamGPSStatus4sendEv)
*(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s)
*(.text._ZN23MavlinkStreamStatustext4sendEv)
*(.text._ZN3Ekf15constrainStatesEv)
*(.text._ZN12PX4IO_serial4readEjPvj)
*(.text.uart_poll)
*(.text._ZN24MavlinkParametersManager4sendEv)
*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_s)
*(.text.file_poll)
*(.text.hrt_elapsed_time)
*(.text._ZN7Mavlink11send_finishEv)
*(.text._ZNK3Ekf36estimateInertialNavFallingLikelihoodEv)
*(.text._ZN15PositionControl16_positionControlEv)
*(.text._ZN28MavlinkStreamDebugFloatArray4sendEv)
*(.text._ZN11ControlMath9limitTiltERN6matrix7Vector3IfEERKS2_f)
*(.text.pthread_mutex_lock)
*(.text._ZN21MavlinkStreamAltitude8get_sizeEv)
*(.text._ZN7Mavlink29check_requested_subscriptionsEv)
*(.text.imxrt_lpspi_setmode)
*(.text._ZN3Ekf34controlZeroInnovationHeadingUpdateEv)
*(.text.perf_begin)
*(.text.imxrt_lpspi_setfrequency)
*(.text._ZN17FlightModeManager9_initTaskE15FlightTaskIndex)
*(.text._ZN22MulticopterRateControl3RunEv)
*(.text.cosf)
*(.text._ZN22MavlinkStreamESCStatus4sendEv)
*(.text._ZN26MavlinkStreamCameraTrigger4sendEv)
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt4sendEv)
*(.text._ZN4uORB12Subscription4copyEPv)
*(.text._ZN7sensors19VehicleAcceleration21SensorSelectionUpdateEb)
*(.text.nxsem_add_holder)
*(.text.crc_accumulate)
*(.text._ZN3px46logger6Logger13update_paramsEv)
*(.text._ZN11calibration14DeviceExternalEm)
*(.text.sq_addafter)
*(.text._ZN25MavlinkStreamHomePosition8get_sizeEv)
*(.text.imxrt_lpspi_modifyreg32)
*(.text._ZN7sensors19VehicleAcceleration16SensorBiasUpdateEb)
*(.text.modifyreg32)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmlEf)
*(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE)
*(.text.imxrt_queuedtd)
*(.text.nxsched_suspend_scheduler)
*(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv)
*(.text._ZN3Ekf16fuseVelPosHeightEffi)
*(.text._ZN3Ekf23controlBaroHeightFusionEv)
*(.text._ZN16PX4Accelerometer9set_scaleEf)
*(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf)
*(.text._ZN22MavlinkStreamEfiStatus4sendEv)
*(.text._ZN22MavlinkStreamDebugVect4sendEv)
*(.text._ZN4EKF217PublishSensorBiasERKy)
*(.text._ZN17FlightModeManager3RunEv)
*(.text._ZN15PositionControl11_inputValidEv)
*(.text._ZN7sensors14VehicleAirData3RunEv)
*(.text.perf_count)
*(.text._ZN3Ekf16controlMagFusionEv)
*(.text.nxsem_clockwait)
*(.text.pthread_sem_give)
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv)
*(.text._ZN4uORB20SubscriptionInterval4copyEPv)
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams)
*(.text.imxrt_epcomplete.constprop.0)
*(.text.imxrt_tcd_free)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_)
*(.text._ZN9Commander30handleModeIntentionAndFailsafeEv)
*(.text.perf_event_count)
*(.text._ZN4EKF215PublishAttitudeERKy)
*(.text._ZN19MavlinkStreamRawRpm8get_sizeEv)
*(.text.nxsem_trywait)
*(.text._ZNK3px46atomicIbE4loadEv)
*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv)
*(.text.pthread_mutex_add)
*(.text._ZN12HomePosition6updateEbb)
*(.text._ZN5PX4IO3RunEv)
*(.text.poll_fdsetup)
*(.text._ZN15PositionControl20_accelerationControlEv)
*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE)
*(.text._ZN9Commander19control_status_ledsEbh)
*(.text._ZN6device3I2C8transferEPKhjPhj)
*(.text.orb_publish)
*(.text._ZN7sensors19VehicleAcceleration16ParametersUpdateEb)
*(.text._ZN22MavlinkStreamVibration8get_sizeEv)
*(.text._ZN15MavlinkReceiver15CheckHeartbeatsERKyb)
*(.text._ZNK6matrix7Vector3IfEmiES1_)
*(.text.__aeabi_f2ulz)
*(.text._ZN9ICM42688P26DataReadyInterruptCallbackEiPvS0_)
*(.text._ZN13land_detector23MulticopterLandDetector23_get_maybe_landed_stateEv)
*(.text.acosf)
*(.text._ZN14ImuDownSampler5resetEv)
*(.text._ZN3Ekf31checkVerticalAccelerationHealthERKN9estimator9imuSampleE)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_)
*(.text.udp_pollsetup)
*(.text.nxsem_timeout)
*(.text._ZL14timer_callbackPv)
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf)
*(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi)
*(.text.nxsem_wait_irq)
*(.text._ZN20MavlinkCommandSender4lockEv)
*(.text.MEM_LongCopyEnd)
*(.text._ZThn24_N16ControlAllocator3RunEv)
*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv)
*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_)
*(.text._ZN17FlightModeManager17start_flight_taskEv)
*(.text.MEM_DataCopyBytes)
*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv)
*(.text._ZN6SticksC1EP12ModuleParams)
*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv)
*(.text._ZN3Ekf35updateHorizontalDeadReckoningstatusEv)
*(.text._ZN3Ekf20controlAirDataFusionERKN9estimator9imuSampleE)
*(.text._ZN24FlightTaskManualAltitudeC1Ev)
*(.text._ZN25MavlinkStreamHomePosition4sendEv)
*(.text._ZN24MavlinkParametersManager8send_oneEv)
*(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_)
*(.text._ZN21HealthAndArmingChecks6updateEb)
*(.text._ZThn24_N22MulticopterRateControl3RunEv)
*(.text._ZN26MavlinkStreamManualControl4sendEv)
*(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv)
*(.text._ZN18mag_bias_estimator16MagBiasEstimator3RunEv)
*(.text._ZN4uORB7Manager11orb_publishEPK12orb_metadataPvPKv)
*(.text._ZN24MavlinkParametersManager18send_untransmittedEv)
*(.text._ZN10MavlinkFTP4sendEv)
*(.text._ZN15ArchPX4IOSerial13_do_interruptEv)
*(.text._ZN3Ekf27controlExternalVisionFusionEv)
*(.text.clock_gettime)
*(.text._ZN3ADC17update_adc_reportEy)
*(.text._ZN3sym25ComputeYaw312InnovVarAndHIfEEvRKN6matrix6MatrixIT_Lj24ELj1EEERKNS2_IS3_Lj23ELj23EEES3_S3_PS3_PNS2_IS3_Lj23ELj1EEE)
*(.text._ZN3Ekf19runTerrainEstimatorERKN9estimator9imuSampleE)
*(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv)
*(.text._ZN9LockGuardD1Ev)
*(.text._ZN4EKF213PublishStatesERKy)
*(.text._ZN3ADC3RunEv)
*(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data)
*(.text._ZN3Ekf20controlFakePosFusionEv)
*(.text._ZN11calibration9Gyroscope13set_device_idEm)
*(.text._ZN24MavlinkStreamOrbitStatus8get_sizeEv)
*(.text.imxrt_progressep)
*(.text.imxrt_gpio_configinput)
*(.text._ZN17FlightModeManager26generateTrajectorySetpointEfRK24vehicle_local_position_s)
*(.text._ZN7Sensors14diff_pres_pollEv)
*(.text._ZN21MavlinkStreamAttitude4sendEv)
*(.text._ZN4EKF220UpdateMagCalibrationERKy)
*(.text._ZN22MavlinkStreamEfiStatus8get_sizeEv)
*(.text._ZN9ICM42688P9DataReadyEv)
*(.text._ZN21MavlinkMissionManager20check_active_missionEv)
*(.text._ZNK3Ekf20get_ekf_vel_accuracyEPfS0_)
*(.text._ZN4EKF216UpdateBaroSampleER17ekf2_timestamps_s)
*(.text._ZN4EKF223UpdateSystemFlagsSampleER17ekf2_timestamps_s)
*(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv)
*(.text._ZN29MavlinkStreamObstacleDistance4sendEv)
*(.text._ZN24MavlinkStreamOrbitStatus4sendEv)
*(.text._ZN16PreFlightChecker26preFlightCheckHeightFailedERK23estimator_innovations_sf)
*(.text._ZN9Navigator3runEv)
*(.text._ZN24MavlinkParametersManager11send_paramsEv)
*(.text._ZN17MavlinkLogHandler4sendEv)
*(.text._ZN7control10SuperBlock5setDtEf)
*(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv)
*(.text.board_autoled_on)
*(.text._ZN5PX4IO13io_get_statusEv)
*(.text._ZN26MulticopterAttitudeControl3RunEv)
*(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason)
*(.text._ZN4EKF218PublishStatusFlagsERKy)
*(.text._ZN11WeatherVaneC1EP12ModuleParams)
*(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s)
*(.text._ZN7Mavlink10send_startEi)
*(.text.imxrt_lpspi_setbits)
*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEf)
*(.text._ZN4EKF222UpdateAccelCalibrationERKy)
*(.text._ZN7sensors19VehicleMagnetometer3RunEv)
*(.text._ZN29MavlinkStreamMountOrientation4sendEv)
*(.text._ZN13land_detector12LandDetector19UpdateVehicleAtRestEv)
*(.text._ZN10FlightTask29_evaluateVehicleLocalPositionEv)
*(.text.board_autoled_off)
*(.text.__aeabi_f2lz)
*(.text._ZN32MavlinkStreamCameraImageCaptured4sendEv)
*(.text._ZN21MavlinkStreamOdometry8get_sizeEv)
*(.text._ZN28MavlinkStreamNamedValueFloat4sendEv)
*(.text.__aeabi_ul2f)
*(.text.poll)
*(.text._ZN14FlightTaskAutoD1Ev)
*(.text._ZN4uORB10DeviceNode22get_initial_generationEv)
*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator9gpsSampleE)
*(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev)
*(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE)
*(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv)
*(.text._ZN22MavlinkStreamScaledIMU4sendEv)
*(.text._ZN46MavlinkStreamTrajectoryRepresentationWaypoints4sendEv)
*(.text.imxrt_ioctl)
*(.text._ZN3Ekf25checkMagBiasObservabilityEv)
*(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv)
*(.text._ZN16PreFlightChecker6updateEfRK23estimator_innovations_s)
*(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0)
*(.text.nxsched_get_tcb)
*(.text._ZN19StickAccelerationXYC1EP12ModuleParams)
*(.text.imxrt_epsubmit)
*(.text._ZN15PositionControl6updateEf)
*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE)
*(.text._ZN23MavlinkStreamScaledIMU24sendEv)
*(.text._ZN5PX4IO10io_reg_getEhhPtj)
*(.text.imxrt_dma_send)
*(.text._ZN20MavlinkStreamWindCov4sendEv)
*(.text._ZN7sensors18VotedSensorsUpdate13checkFailoverERNS0_10SensorDataEPKcN6events3px45enums13sensor_type_tE)
*(.text._ZN21MavlinkStreamOdometry4sendEv)
*(.text.vsprintf_internal.constprop.0)
*(.text.udp_pollteardown)
*(.text._ZN12MixingOutput6updateEv)
*(.text.clock_abstime2ticks)
*(.text._ZN13BatteryStatus3RunEv)
*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv)
*(.text._ZN10FlightTask15_resetSetpointsEv)
*(.text._ZN9systemlib10Hysteresis20set_state_and_updateEbRKy)
*(.text.devif_callback_free.part.0)
*(.text._ZN6Sticks25checkAndUpdateStickInputsEv)
*(.text.atan2f)
*(.text._ZN23MavlinkStreamRCChannels4sendEv)
*(.text.sq_remfirst)
*(.text._ZN4EKF221UpdateExtVisionSampleER17ekf2_timestamps_s)
*(.text.imxrt_dmach_stop)
*(.text._ZN9Commander16handleAutoDisarmEv)
*(.text._ZN9Commander11updateTunesEv)
*(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s)
*(.text._ZN18DataValidatorGroup3putEjyPKfmh)
*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_)
*(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE)
*(.text._ZN17FlightTaskDescendD1Ev)
*(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv)
*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE)
*(.text._ZN24FlightTaskManualAltitudeD1Ev)
*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb)
*(.text.uart_pollnotify)
*(.text._ZN3Ekf11predictHaglERKN9estimator9imuSampleE)
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh4EE16advertised_countEv)
*(.text._ZN23MavlinkStreamScaledIMU34sendEv)
*(.text.__aeabi_ldivmod)
*(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s)
*(.text.nxsig_pendingset)
*(.text.psock_poll)
*(.text._ZN15FailureInjector6updateEv)
*(.text.imxrt_writedtd)
*(.text.cdcacm_wrcomplete)
*(.text.cdcuart_txint)
*(.text._ZN3Ekf33updateVerticalDeadReckoningStatusEv)
*(.text._ZN33FlightTaskManualAltitudeSmoothVelC1Ev)
*(.text.powf)
*(.text._ZN4EKF217PublishEventFlagsERKy)
*(.text.sq_remafter)
*(.text._ZN17FlightTaskDescend6updateEv)
*(.text.imxrt_iomux_configure)
*(.text.hrt_store_absolute_time)
*(.text.nxsem_set_protocol)
*(.text.write)
*(.text._ZN22MavlinkStreamSysStatus4sendEv)
*(.text._ZN4EKF216UpdateFlowSampleER17ekf2_timestamps_s)
*(.text._ZN4cdevL10cdev_ioctlEP4fileim)
*(.text._ZN7Mavlink10send_bytesEPKhj)
*(.text._ZNK8Failsafe17checkModeFallbackERK16failsafe_flags_sh)
*(.text.clock_systime_timespec)
*(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv)
*(.text._ZThn16_N4EKF23RunEv)
*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj23EEE)
*(.text._ZN12ActuatorTest6updateEif)
*(.text._ZN17VelocitySmoothingC1Efff)
*(.text._ZN13AnalogBattery19get_voltage_channelEv)
*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv)
*(.text._ZN4uORB12Subscription11unsubscribeEv)
*(.text.net_lock)
*(.text.clock_time2ticks)
*(.text._ZN12FailsafeBase16updateStartDelayERKyb)
*(.text._ZN23MavlinkStreamStatustext8get_sizeEv)
*(.text._ZN11calibration13Accelerometer13set_device_idEm)
*(.text._ZN3px46logger6Logger18start_stop_loggingEv)
*(.text._ZN14FlightTaskAuto17_evaluateTripletsEv)
*(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb)
*(.text._ZN25MavlinkStreamMagCalReport4sendEv)
*(.text._ZN16PreFlightChecker27preFlightCheckHeadingFailedERK23estimator_innovations_sf)
*(.text.imxrt_config_gpio)
*(.text.nxsig_timeout)
*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_)
*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj23EEEff)
*(.text.dq_addlast)
*(.text._ZN19MavlinkStreamVFRHUD4sendEv)
*(.text.hrt_call_reschedule)
*(.text.nxsem_boost_priority)
*(.text._ZN4EKF215UpdateGpsSampleER17ekf2_timestamps_s)
*(.text._ZN8StickYawC1EP12ModuleParams)
*(.text._ZN7control12BlockLowPass6updateEf)
*(.text._ZN15FailureDetector26updateImbalancedPropStatusEv)
*(.text._ZN9systemlib10Hysteresis6updateERKy)
*(.text.nxsem_tickwait_uninterruptible)
*(.text._ZN12HomePosition31hasMovedFromCurrentHomeLocationEv)
*(.text.devif_callback_alloc)
*(.text._ZN28MavlinkStreamNamedValueFloat8get_sizeEv)
*(.text._ZN24MavlinkStreamADSBVehicle8get_sizeEv)
*(.text._ZN26MavlinkStreamBatteryStatus8get_sizeEv)
*(.text._ZN26MulticopterPositionControl17parameters_updateEb)
*(.text._ZN3px46logger6Logger29handle_vehicle_command_updateEv)
*(.text.imxrt_lpspi_send)
*(.text._ZN4uORB10DeviceNode23add_internal_subscriberEv)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEaSERKS1_)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_)
*(.text.mallinfo_handler)
*(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv)
*(.text._ZN24ManualVelocitySmoothingZC1Ev)
*(.text._ZN3ADC6sampleEj)
*(.text._ZNK3Ekf22isTerrainEstimateValidEv)
*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report)
*(.text._ZN11ControlMath11addIfNotNanERff)
*(.text._ZN9Commander21checkForMissionUpdateEv)
*(.text._Z8set_tunei)
*(.text._ZN3Ekf13stopGpsFusionEv)
*(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE)
*(.text._ZN10FlightTask22_checkEkfResetCountersEv)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv)
*(.text._ZN14FlightTaskAuto24_evaluateGlobalReferenceEv)
*(.text._ZN6matrix9constrainIfLj2ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
*(.text._ZN3px46logger6Logger23handle_file_write_errorEv)
*(.text._ZN10FlightTask16updateInitializeEv)
*(.text._ZN11calibration9Gyroscope10set_offsetERKN6matrix7Vector3IfEE)
*(.text._ZNK6matrix6VectorIfLj3EE4normEv)
*(.text._ZN14FlightTaskAuto16updateInitializeEv)
*(.text.fabsf)
*(.text._ZN27MavlinkStreamAttitudeTarget8get_sizeEv)
*(.text.nxsem_get_value)
*(.text._ZN13AnalogBattery8is_validEv)
*(.text._ZN4uORB16SubscriptionDataI15home_position_sEC1EPK12orb_metadatah)
*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv)
*(.text.nxsem_destroyholder)
*(.text.psock_udp_cansend)
*(.text.MEM_DataCopy2_2)
*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s)
*(.text.sock_file_poll)
*(.text._ZN3Ekf20controlHaglRngFusionEv)
*(.text._ZN10Ringbuffer9pop_frontEPhj)
*(.text.nx_write)
*(.text._ZN9Commander18manualControlCheckEv)
*(.text._ZN31MavlinkStreamAttitudeQuaternion4sendEv)
*(.text.nxsem_canceled)
*(.text._ZN10FlightTask21getTrajectorySetpointEv)
*(.text.imxrt_dmach_getcount)
*(.text.sem_clockwait)
*(.text.inet_poll)
*(.text._ZN6BMP3887collectEv)
*(.text._ZN15ArchPX4IOSerial19_do_rx_dma_callbackEbi)
*(.text._ZN15ArchPX4IOSerial10_abort_dmaEv)
*(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s)
*(.text._ZN3Ekf16controlGpsFusionERKN9estimator9imuSampleE)
*(.text._ZN23MavlinkStreamRCChannels8get_sizeEv)
*(.text._ZN20MavlinkStreamESCInfo8get_sizeEv)
*(.text._ZNK6matrix6VectorIfLj2EE4normEv)
*(.text._Z15arm_auth_updateyb)
*(.text.imxrt_lpi2c_isr)
*(.text._ZN3LED5ioctlEP4fileim)
*(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv)
*(.text._ZN29MavlinkStreamLocalPositionNED4sendEv)
*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ILj3ELj1EEERKNS_5SliceIfLj2ELj1EXT_EXT0_EEE)
*(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE)
*(.text.imxrt_lpi2c_setclock)
*(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0)
*(.text._ZN13MapProjection13initReferenceEddy)
*(.text._ZN11calibration13Accelerometer23SensorCorrectionsUpdateEb)
*(.text._ZN31MavlinkStreamAttitudeQuaternion8get_sizeEv)
*(.text._ZN30MavlinkStreamGlobalPositionInt4sendEv)
*(.text._ZN6SticksD1Ev)
*(.text._ZN13NavigatorMode3runEb)
*(.text._ZL19param_find_internalPKcb)
*(.text.uart_datasent)
*(.text._ZN4EKF221PublishOpticalFlowVelERKy)
*(.text.nxsem_destroy)
*(.text.file_write)
*(.text._ZN21MavlinkStreamAltitude4sendEv)
*(.text._ZN7sensors14VehicleAirData12UpdateStatusEv)
*(.text.imxrt_padmux_map)
*(.text._ZN6BMP38815get_sensor_dataEhP9bmp3_data)
*(.text._ZN18MavlinkRateLimiter5checkERKy)
*(.text._ZThn24_N26MulticopterAttitudeControl3RunEv)
*(.text._ZN15ArchPX4IOSerial10_interruptEiPvS0_)
*(.text.imxrt_periphclk_configure)
*(.text._ZN3Ekf8initHaglEv)
*(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s)
*(.text._ZN3RTL11on_inactiveEv)
*(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh)
*(.text._ZN4EKF216PublishEvPosBiasERKy)
*(.text._ZN21MavlinkStreamAttitude8get_sizeEv)
*(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv)
*(.text.imxrt_timerisr)
*(.text._ZN3Ekf24controlRangeHeightFusionEv)
*(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv)
*(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf)
*(.text._ZN12ModuleParamsD1Ev)
*(.text._ZN3Ekf20controlFakeHgtFusionEv)
*(.text.sq_addlast)
*(.text.imxrt_reqcomplete)
*(.text._ZNK6matrix7Vector3IfEmlEf)
*(.text._ZN18ZeroVelocityUpdate6updateER3EkfRKN9estimator9imuSampleE)
*(.text._ZN11ControlMath19addIfNotNanVector3fERN6matrix7Vector3IfEERKS2_)
*(.text._ZN11ControlMath16thrustToAttitudeERKN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s)
*(.text.cos)
*(.text.net_unlock)
*(.text._ZN7sensors18VotedSensorsUpdate21setRelativeTimestampsER17sensor_combined_s)
*(.text._ZN12FailsafeBase13ActionOptionsC1ENS_6ActionE)
*(.text._ZN24FlightTaskManualAltitude16updateInitializeEv)
*(.text._ZN26MulticopterPositionControl3RunEv)
*(.text._ZN8Failsafe21fromQuadchuteActParamEi)
*(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj)
*(.text._ZN7control15BlockDerivative6updateEf)
*(.text._ZN5PX4IO10io_reg_getEhh)
*(.text._ZN9Commander18safetyButtonUpdateEv)
*(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN18DataValidatorGroup16get_sensor_stateEj)
*(.text.uart_xmitchars_done)
*(.text.nxsched_get_files)
*(.text._ZN4EKF225PublishYawEstimatorStatusERKy)
*(.text.sin)
*(.text._ZN16PreFlightChecker27preFlightCheckVertVelFailedERK23estimator_innovations_sf)
*(.text._ZN6Safety19safetyButtonHandlerEv)
*(.text._ZN3Ekf19controlAuxVelFusionEv)
*(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_)
*(.text._ZThn24_N7Sensors3RunEv)
*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_)
*(.text._ZN10FlightTask10reActivateEv)
*(.text._ZN5PX4IO17io_publish_raw_rcEv)
*(.text._ZNK15PositionControl19getAttitudeSetpointER27vehicle_attitude_setpoint_s)
*(.text._ZN4cdev4CDev4pollEP4fileP6pollfdb)
*(.text._ZN9Commander20offboardControlCheckEv)
*(.text._ZN4EKF216PublishGpsStatusERKy)
*(.text._ZN4uORB12SubscriptionaSEOS0_)
*(.text._ZN15TakeoffHandling18updateTakeoffStateEbbbfbRKy)
*(.text._ZN10ModeChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN14FlightTaskAuto24_updateInternalWaypointsEv)
*(.text._ZN8Failsafe17updateArmingStateERKybRK16failsafe_flags_s)
*(.text.imxrt_lpi2c_modifyreg)
*(.text.up_flush_dcache)
*(.text._ZN5PX4IO16io_handle_statusEt)
*(.text._ZN15GyroCalibration3RunEv)
*(.text.mavlink_start_uart_send)
*(.text.MEM_DataCopy2)
*(.text._ZNK9Commander14getPrearmStateEv)
*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28FlightTaskManualAccelerationD1Ev)
*(.text._ZN11RateControl20getRateControlStatusER18rate_ctrl_status_s)
*(.text._ZN4uORB10DeviceNode15poll_notify_oneEP6pollfdm)
*(.text._ZN3GPS21handleInjectDataTopicEv.part.0)
*(.text._ZN9Commander17systemPowerUpdateEv)
*(.text._ZN4EKF221PublishGlobalPositionERKy)
*(.text._ZNK12FailsafeBase17getSelectedActionERKNS_5StateERK16failsafe_flags_sbbRNS_19SelectedActionStateE)
*(.text.imxrt_padctl_address)
*(.text._ZNK6matrix6VectorIfLj2EE4unitEv)
*(.text._ZN19RcCalibrationChecks14checkAndReportERK7ContextR6Report)
*(.text.devif_conn_callback_free)
*(.text._ZN13InnovationLpf6updateEfff.isra.0)
*(.text._ZN9Commander18landDetectorUpdateEv)
*(.text._ZN3Ekf18updateGroundEffectEv)
*(.text.nxsem_init)
*(.text._ZN9Commander16vtolStatusUpdateEv)
*(.text._ZN6matrix6MatrixIfLj4ELj1EEC1EPKf)
*(.text._ZN11ControlMath20setZeroIfNanVector3fERN6matrix7Vector3IfEE)
*(.text._ZThn8_N3ADC3RunEv)
*(.text._ZN11StickTiltXYC1EP12ModuleParams)
*(.text._ZN12SafetyButton3RunEv)
*(.text.arm_ack_irq)
*(.text._ZN6BMP38811set_op_modeEh)
*(.text._ZN3GPS8callbackE15GPSCallbackTypePviS1_)
*(.text._ZN13AnalogBattery19get_current_channelEv)
*(.text._ZN15EstimatorChecks20checkEstimatorStatusERK7ContextR6ReportRK18estimator_status_s8NavModes)
*(.text._ZN12FailsafeBase11updateDelayERKy)
*(.text._ZN10FlightTask25_evaluateDistanceToGroundEv)
*(.text._ZN4EKF218PublishGnssHgtBiasERKy)
*(.text._ZN3Ekf21controlHaglFlowFusionEv)
*(.text._ZN6matrix6VectorIfLj3EE9normalizeEv)
*(.text._ZThn16_N7sensors10VehicleIMU3RunEv)
*(.text.__kernel_cos)
*(.text._ZN12SafetyButton19CheckPairingRequestEb)
*(.text.imxrt_dma_txavailable)
*(.text.perf_set_elapsed)
*(.text.pthread_sem_take)
*(.text._ZN8StickYawD1Ev)
*(.text._Z15blink_msg_statev)
*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN8Failsafe14fromGfActParamEi)
*(.text._ZN3Ekf27checkAndFixCovarianceUpdateERKN6matrix12SquareMatrixIfLj23EEE)
*(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE)
*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev)
*(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf)
*(.text._ZN17FlightTaskDescendC1Ev)
*(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv)
*(.text.iob_navail)
*(.text._ZN12FailsafeBase25removeNonActivatedActionsEv)
*(.text._ZN16PreFlightChecker28preFlightCheckHorizVelFailedERK23estimator_innovations_sf)
*(.text._ZN15TakeoffHandling10updateRampEff)
*(.text._Z7led_offi)
*(.text._ZN16PreFlightChecker22selectHeadingTestLimitEv)
*(.text.led_off)
*(.text.udp_wrbuffer_test)
*(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s)
*(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv)
*(.text._ZN27MavlinkStreamAttitudeTarget4sendEv)
*(.text._ZN12MixingOutput19updateSubscriptionsEb)
*(.text._ZN10FlightTaskD1Ev)
*(.text._ZThn24_N13land_detector12LandDetector3RunEv)
*(.text._ZN18MavlinkStreamDebug8get_sizeEv)
*(.text._ZN12GPSDriverUBX7receiveEj)
*(.text._ZN13BatteryStatus21parameter_update_pollEb)
*(.text._ZN3Ekf26checkYawAngleObservabilityEv)
*(.text._ZN3RTL18updateDatamanCacheEv)
*(.text.__ieee754_sqrtf)
*(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv)
*(.text.__kernel_sin)
*(.text._ZN11MissionBase17parameters_updateEv)
*(.text.nx_start)
*(.text._ZN3Ekf17controlDragFusionERKN9estimator9imuSampleE)
*(.text._ZNK8Failsafe22modifyUserIntendedModeEN12FailsafeBase6ActionES1_h)
*(.text._ZN3px417ScheduledWorkItem19schedule_trampolineEPv)
*(.text.uart_xmitchars_dma)
*(.text._ZN13land_detector23MulticopterLandDetector19_get_freefall_stateEv)
*(.text._ZThn24_N31MulticopterHoverThrustEstimator3RunEv)
*(.text._ZN11MissionBase11on_inactiveEv)
*(.text._ZN21FailureDetectorChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf)
*(.text.imxrt_padmux_address)
*(.text._ZN3Ekf15setVelPosStatusEib)
*(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv)
*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes)
*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN17ObstacleAvoidanceD1Ev)
*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv)
*(.text.MEM_DataCopy2_1)
*(.text._ZN6BMP3887measureEv)
*(.text._ZN4EKF217PublishRngHgtBiasERKy)
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv)
*(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv)
*(.text.up_clean_dcache)
*(.text._ZThn56_N26MulticopterPositionControl3RunEv)
*(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN13ManualControl12processInputEy)
*(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN10GyroChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN8Failsafe26fromImbalancedPropActParamEi)
*(.text._ZThn24_N13BatteryStatus3RunEv)
*(.text.mm_foreach)
*(.text._ZN35MavlinkStreamPositionTargetLocalNed8get_sizeEv)
*(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv)
*(.text._ZN6matrix8wrap_2piIfEET_S1_)
*(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv)
*(.text._ZN10BMP388_I2C7get_regEh)
*(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv)
*(.text._ZN30MavlinkStreamUTMGlobalPosition10const_rateEv)
*(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv)
*(.text._ZN3RTL17parameters_updateEv)
*(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0)
*(.text._ZN32MavlinkStreamOpenDroneIdLocation8get_sizeEv)
*(.text._ZN21MavlinkStreamTimesync4sendEv)
*(.text._ZN9Navigator23reset_position_setpointER19position_setpoint_s)
*(.text._ZN19RcAndDataLinkChecks14checkAndReportERK7ContextR6Report)
*(.text.imxrt_dma_txcallback)
*(.text._ZN24MavlinkParametersManager11send_uavcanEv)
*(.text._ZN4uORB10DeviceNode4readEP4filePcj)
*(.text._ZN4uORB10DeviceNode10poll_stateEP4file)
*(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv)
*(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv)
*(.text._ZN30MavlinkStreamUTMGlobalPosition8get_sizeEv)
*(.text._ZN8Geofence3runEv)
*(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s)
*(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN6events9SendEvent3RunEv)
*(.text._ZN30MavlinkStreamGlobalPositionInt8get_sizeEv)
*(.text._ZN22MavlinkStreamESCStatus8get_sizeEv)
*(.text._Z20px4_spi_bus_externalRK13px4_spi_bus_t)
*(.text.read)
*(.text._ZN4uORB15PublicationBaseD1Ev)
*(.text._ZN22MavlinkStreamDebugVect8get_sizeEv)
*(.text._ZN22MavlinkStreamCollision8get_sizeEv)
*(.text._ZN7Mission11on_inactiveEv)
*(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv)
*(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm)
*(.text._ZN4cdevL9cdev_readEP4filePcj)
*(.text.sem_timedwait)
*(.text.snprintf)
*(.text._ZN27MavlinkStreamOpticalFlowRad8get_sizeEv)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE6copyToEPf)
*(.text._ZN6Report13healthFailureIJhEEEv8NavModes20HealthComponentIndexmRKN6events9LogLevelsEPKcDpT_.isra.0.constprop.0)
*(.text._ZN13BatteryChecks16rtlEstimateCheckERK7ContextR6Reportf)
*(.text.sigemptyset)
*(.text.nx_read)
@@ -1,197 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/* Specify the memory areas */
/* Reallocate
* Final Configuration is
* No DTCM
* 512k OCRAM M7 (FlexRAM) (2038:0000-203f:ffff)
* 128k OCRAMM7 FlexRAM ECC (2036:0000-2037:ffff)
* 64k OCRAM2 ECC parity (2035:0000-2035:ffff)
* 64k OCRAM1 ECC parity (2034:0000-2034:ffff)
* 512k FlexRAM OCRAM2 (202C:0000-2033:ffff)
* 512k FlexRAM OCRAM1 (2024:0000-202B:ffff)
* 256k System OCRAM M4 (2020:0000-2023:ffff)
*/
MEMORY
{
flash (rx) : ORIGIN = 0x30020000, LENGTH = 4M-128K /* We have 64M but we do not want to wait to program it all */
sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k-512k
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 256K /* TODO FlexRAM partition */
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 256K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
EXTERN(g_flash_config)
EXTERN(g_image_vector_table)
EXTERN(g_boot_data)
EXTERN(board_get_manifest)
EXTERN(_bootdelay_signature)
EXTERN(imxrt_flexspi_initialize)
ENTRY(__start)
SECTIONS
{
/* Image Vector Table and Boot Data for booting from external flash */
.boot_hdr : ALIGN(4)
{
FILL(0xff)
. = 0x400 ;
__boot_hdr_start__ = ABSOLUTE(.) ;
KEEP(*(.boot_hdr.conf))
. = 0x1000 ;
KEEP(*(.boot_hdr.ivt))
. = 0x1020 ;
KEEP(*(.boot_hdr.boot_data))
. = 0x1030 ;
KEEP(*(.boot_hdr.dcd_data))
__boot_hdr_end__ = ABSOLUTE(.) ;
. = 0x2000 ;
} >flash
.vectors :
{
KEEP(*(.vectors))
*(.text .text.__start)
} >flash
.itcmfunc :
{
. = ALIGN(8);
_sitcmfuncs = ABSOLUTE(.);
FILL(0xFF)
. = 0x40 ;
INCLUDE "itcm_functions_includes.ld"
. = ALIGN(8);
_eitcmfuncs = ABSOLUTE(.);
} > itcm AT > flash
_fitcmfuncs = LOADADDR(.itcmfunc);
/* The RAM vector table (if present) should lie at the beginning of SRAM */
.ram_vectors (COPY) : {
*(.ram_vectors)
} > dtcm
.text : ALIGN(4)
{
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
. = ALIGN(4096);
_etext = ABSOLUTE(.);
_srodata = ABSOLUTE(.);
*(.rodata .rodata.*)
. = ALIGN(4096);
_erodata = ABSOLUTE(.);
} > flash
.init_section :
{
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab :
{
*(.ARM.extab*)
} > flash
.ARM.exidx :
{
__exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
__exidx_end = ABSOLUTE(.);
} > flash
_eronly = ABSOLUTE(.);
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.ramfunc ALIGN(4):
{
_sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > flash
_framfuncs = LOADADDR(.ramfunc);
.bss :
{
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
_boot_loadaddr = ORIGIN(flash);
_boot_size = LENGTH(flash);
_ram_size = LENGTH(sram);
_sdtcm = ORIGIN(dtcm);
_edtcm = ORIGIN(dtcm) + LENGTH(dtcm);
}
-92
View File
@@ -1,92 +0,0 @@
############################################################################
#
# Copyright (c) 2016, 2019, 2023 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
add_compile_definitions(BOOTLOADER)
add_library(drivers_board
bootloader_main.c
init.c
usb.c
imxrt_romapi.c
imxrt_flexspi_nor_boot.c
imxrt_flexspi_nor_flash.c
imxrt_clockconfig.c
timer_config.cpp
)
target_link_libraries(drivers_board
PRIVATE
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer #gpio
arch_io_pins # iotimer
bootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
else()
if(CONFIG_IMXRT1170_FLEXSPI_FRAM)
list(APPEND SRCS
imxrt_flexspi_fram.c
)
endif()
px4_add_library(drivers_board
autoleds.c
automount.c
#can.c
i2c.cpp
init.c
led.c
manifest.c
mtd.cpp
sdhc.c
spi.cpp
timer_config.cpp
usb.c
imxrt_romapi.c
imxrt_flexspi_fram.c
imxrt_flexspi_nor_boot.c
imxrt_flexspi_nor_flash.c
imxrt_clockconfig.c
${SRCS}
)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)
endif()
-663
View File
@@ -1,663 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* PX4 fmu-v6xrt internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include "imxrt_gpio.h"
#include "imxrt_iomuxc.h"
#include "hardware/imxrt_pinmux.h"
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* PX4IO connection configuration */
// This requires serial DMA driver
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
#define PX4IO_SERIAL_TX_GPIO GPIO_LPUART6_TX
#define PX4IO_SERIAL_RX_GPIO GPIO_LPUART6_RX
#define PX4IO_SERIAL_BASE IMXRT_LPUART6_BASE
#define PX4IO_SERIAL_VECTOR IMXRT_IRQ_LPUART6
#define PX4IO_SERIAL_TX_DMAMAP IMXRT_DMACHAN_LPUART6_TX
#define PX4IO_SERIAL_RX_DMAMAP IMXRT_DMACHAN_LPUART6_RX
#define PX4IO_SERIAL_CLOCK_OFF imxrt_clockoff_lpuart6
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
/* Configuration ************************************************************************************/
/* Configuration ************************************************************************************/
#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks
#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid
#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage
#define BOARD_HAS_NBAT_I 2d // 2 Digital Current
/* FMU-V6XRT GPIOs ***********************************************************************************/
/* LEDs */
/* An RGB LED is connected through GPIO as shown below:
*/
#define LED_IOMUX (IOMUX_OPENDRAIN | IOMUX_PULL_NONE)
#define GPIO_nLED_RED /* GPIO_DISP_B2_00 GPIO5_IO01 */ (GPIO_PORT5 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_GREEN /* GPIO_DISP_B2_01 GPIO5_IO02 */ (GPIO_PORT5 | GPIO_PIN2 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_BLUE /* GPIO_EMC_B1_13 GPIO1_IO13 */ (GPIO_PORT1 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_BLUE
/* I2C busses */
/* Devices on the onboard buses.
*
* Note that these are unshifted addresses.
*/
#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/
#define PX4_I2C_OBDEV_SE050 0x48
/*
* From the radion souce code
* // Serial flow control
* #define SERIAL_RTS PIN_ENABLE // always an input
* #define SERIAL_CTS PIN_CONFIG // input in bootloader, output in app
*
* RTS is an out from FMU
* CTS is in input to the FMU but the booloader on the radion will treat it as an input, and the
* radion APP as output.
*
* To ensure radios do not go into bootloader mode because our CTS is configured with Pull downs
* We init with pull ups, then enable power, then initalize the CTS will pull downs
*/
#define GPIO_LPUART4_CTS_INIT PX4_MAKE_GPIO_PULLED_INPUT(GPIO_LPUART4_CTS, IOMUX_PULL_UP)
#define GPIO_LPUART8_CTS_INIT PX4_MAKE_GPIO_PULLED_INPUT(GPIO_LPUART8_CTS, IOMUX_PULL_UP)
#define GPIO_LPUART10_CTS_INIT PX4_MAKE_GPIO_PULLED_INPUT(GPIO_LPUART10_CTS,IOMUX_PULL_UP)
/*
* Define the ability to shut off off the sensor signals
* by changing the signals to inputs
*/
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN))
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */
#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST)
#define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST)
/* SPI1 off */
#define _GPIO_LPSPI1_SCK /* GPIO_EMC_B2_00 GPIO2_IO10 */ (GPIO_PORT2 | GPIO_PIN10 | CS_IOMUX)
#define _GPIO_LPSPI1_MISO /* GPIO_EMC_B2_03 GPIO2_IO13 */ (GPIO_PORT2 | GPIO_PIN13 | CS_IOMUX)
#define _GPIO_LPSPI1_MOSI /* GPIO_EMC_B2_02 GPIO2_IO12 */ (GPIO_PORT2 | GPIO_PIN12 | CS_IOMUX)
#define GPIO_SPI1_SCK_OFF _PIN_OFF(_GPIO_LPSPI1_SCK)
#define GPIO_SPI1_MISO_OFF _PIN_OFF(_GPIO_LPSPI1_MISO)
#define GPIO_SPI1_MOSI_OFF _PIN_OFF(_GPIO_LPSPI1_MOSI)
/* SPI2 off */
#define _GPIO_LPSPI2_SCK /* GPIO_AD_24 GPIO3_IO23 */ (GPIO_PORT3 | GPIO_PIN23 | CS_IOMUX)
#define _GPIO_LPSPI2_MISO /* GPIO_AD_27 GPIO3_IO26 */ (GPIO_PORT3 | GPIO_PIN26 | CS_IOMUX)
#define _GPIO_LPSPI2_MOSI /* GPIO_AD_26 GPIO3_IO25 */ (GPIO_PORT3 | GPIO_PIN25 | CS_IOMUX)
#define GPIO_SPI2_SCK_OFF _PIN_OFF(_GPIO_LPSPI2_SCK)
#define GPIO_SPI2_MISO_OFF _PIN_OFF(_GPIO_LPSPI2_MISO)
#define GPIO_SPI2_MOSI_OFF _PIN_OFF(_GPIO_LPSPI2_MOSI)
/* SPI3 off */
#define _GPIO_LPSPI3_SCK /* GPIO_EMC_B2_04 GPIO2_IO14 */ (GPIO_PORT2 | GPIO_PIN14 | CS_IOMUX)
#define _GPIO_LPSPI3_MISO /* GPIO_EMC_B2_07 GPIO2_IO17 */ (GPIO_PORT2 | GPIO_PIN17 | CS_IOMUX)
#define _GPIO_LPSPI3_MOSI /* GPIO_EMC_B2_06 GPIO2_IO16 */ (GPIO_PORT2 | GPIO_PIN16 | CS_IOMUX)
#define GPIO_SPI3_SCK_OFF _PIN_OFF(_GPIO_LPSPI3_SCK)
#define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO)
#define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI)
/* SPI4 off */
#define _GPIO_LPSPI4_SCK /* GPIO_DISP_B2_12 GPIO5_IO13 */ (GPIO_PORT5 | GPIO_PIN13 | CS_IOMUX)
#define _GPIO_LPSPI4_MISO /* GPIO_DISP_B2_13 GPIO5_IO14 */ (GPIO_PORT5 | GPIO_PIN14 | CS_IOMUX)
#define _GPIO_LPSPI4_MOSI /* GPIO_DISP_B2_14 GPIO5_IO15 */ (GPIO_PORT5 | GPIO_PIN15 | CS_IOMUX)
#define GPIO_SPI4_SCK_OFF _PIN_OFF(_GPIO_LPSPI4_SCK)
#define GPIO_SPI4_MISO_OFF _PIN_OFF(_GPIO_LPSPI4_MISO)
#define GPIO_SPI4_MOSI_OFF _PIN_OFF(_GPIO_LPSPI4_MOSI)
/* SPI6 off */
#define _GPIO_LPSPI6_SCK /* GPIO_LPSR_10 GPIO6_IO10 */ (GPIO_PORT6 | GPIO_PIN10 | CS_IOMUX)
#define _GPIO_LPSPI6_MISO /* GPIO_LPSR_12 GPIO6_IO12 */ (GPIO_PORT6 | GPIO_PIN12 | CS_IOMUX)
#define _GPIO_LPSPI6_MOSI /* GPIO_LPSR_11 GPIO6_IO11 */ (GPIO_PORT6 | GPIO_PIN11 | CS_IOMUX)
#define GPIO_SPI6_SCK_OFF _PIN_OFF(_GPIO_LPSPI6_SCK)
#define GPIO_SPI6_MISO_OFF _PIN_OFF(_GPIO_LPSPI6_MISO)
#define GPIO_SPI6_MOSI_OFF _PIN_OFF(_GPIO_LPSPI6_MOSI)
/* Define the SPI Data Ready and Control signals */
#define DRDY_IOMUX (IOMUX_PULL_UP)
/* SPI1 */
#define GPIO_SPI1_DRDY1_SENSOR1 /* GPIO_AD_20 GPIO3_IO19 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI2_DRDY1_SENSOR2 /* GPIO_EMC_B1_39 GPIO2_IO07 */ (GPIO_PORT2 | GPIO_PIN07 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI3_DRDY1_SENSOR3 /* GPIO_AD_21 GPIO3_IO20 */ (GPIO_PORT3 | GPIO_PIN20 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI3_DRDY2_SENSOR3 /* GPIO_EMC_B2_09 GPIO2_IO19 */ (GPIO_PORT2 | GPIO_PIN19 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI4_DRDY1_SENSOR4 /* GPIO_EMC_B1_16 GPIO1_IO16 */ (GPIO_PORT1 | GPIO_PIN16 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI6_DRDY1_EXTERNAL1 /* GPIO_EMC_B1_05 GPIO1_IO05 */ (GPIO_PORT1 | GPIO_PIN05 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI6_DRDY2_EXTERNAL1 /* GPIO_EMC_B1_07 GPIO1_IO07 */ (GPIO_PORT1 | GPIO_PIN07 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI6_nRESET_EXTERNAL1 /* GPIO_EMC_B1_11 GPIO1_IO11 */ (GPIO_PORT1 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_SPIX_SYNC /* GPIO_EMC_B1_18 GPIO1_IO18 */ (GPIO_PORT1 | GPIO_PIN18 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_DRDY_OFF_SPI6_DRDY2_EXTERNAL1 _PIN_OFF(GPIO_SPI6_DRDY2_EXTERNAL1)
#define GPIO_SPI6_nRESET_EXTERNAL1_OFF _PIN_OFF(GPIO_SPI6_nRESET_EXTERNAL1)
#define GPIO_SPIX_SYNC_OFF _PIN_OFF(GPIO_SPIX_SYNC)
#define ADC_IOMUX (IOMUX_PULL_NONE)
#define ADC1_CH(n) (n)
/* N.B. there is no offset mapping needed for ADC3 because we are only use ADC2 for REV/VER. */
#define ADC2_CH(n) (n)
#define ADC_GPIO(n, p) (GPIO_PORT3 | GPIO_PIN##p | GPIO_INPUT | ADC_IOMUX) //
/* Define GPIO pins used as ADC
* ADC1 has 12 inputs 0-5A and 0-5B
* We represent this as:
* 0 ADC1 CH0A
* 1 ADC1 CH0B
* ...
* 10 ADC1 CH5A
* 11 ADC1 CH5B
*
* ADC2 has 14 inputs 0-6A and 0-6B
*
* 0 ADC2 CH0A
* 1 ADC2 CH0B
* ...
* 12 ADC2 CH6A
* 13 ADC2 CH6B
*
*
*
* */
#define PX4_ADC_GPIO \
/* SCALED_VDD_3V3_SENSORS1 GPIO_AD_10 GPIO3 Pin 9 ADC1_CH2A */ ADC_GPIO(4, 9), \
/* SCALED_VDD_3V3_SENSORS2 GPIO_AD_11 GPIO3 Pin 10 ADC1_CH2B */ ADC_GPIO(5, 10), \
/* SCALED_VDD_3V3_SENSORS3 GPIO_AD_12 GPIO3 Pin 11 ADC1_CH3A */ ADC_GPIO(6, 11), \
/* SCALED_V5 GPIO_AD_13 GPIO3 Pin 12 ADC1_CH3B */ ADC_GPIO(7, 12), \
/* ADC_6V6 GPIO_AD_14 GPIO3 Pin 13 ADC1_CH4A */ ADC_GPIO(8, 13), \
/* ADC_3V3 GPIO_AD_16 GPIO3 Pin 15 ADC1_CH5A */ ADC_GPIO(10, 15), \
/* SCALED_VDD_3V3_SENSORS4 GPIO_AD_17 GPIO3 Pin 16 ADC1_CH5B */ ADC_GPIO(11, 16), \
/* HW_VER_SENSE GPIO_AD_22 GPIO3 Pin 21 ADC2_CH2A */ ADC_GPIO(4, 21), \
/* HW_REV_SENSE GPIO_AD_23 GPIO3 Pin 22 ADC2_CH2B */ ADC_GPIO(5, 22)
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* GPIO_AD_10 GPIO3 Pin 9 ADC1_CH2A */ ADC1_CH(4)
#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* GPIO_AD_11 GPIO3 Pin 10 ADC1_CH2B */ ADC1_CH(5)
#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* GPIO_AD_12 GPIO3 Pin 11 ADC1_CH3A */ ADC1_CH(6)
#define ADC_SCALED_V5_CHANNEL /* GPIO_AD_13 GPIO3 Pin 12 ADC1_CH3B */ ADC1_CH(7)
#define ADC_ADC_6V6_CHANNEL /* GPIO_AD_14 GPIO3 Pin 13 ADC1_CH4A */ ADC1_CH(8)
#define ADC_ADC_3V3_CHANNEL /* GPIO_AD_16 GPIO3 Pin 15 ADC1_CH5A */ ADC1_CH(10)
#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* GPIO_AD_17 GPIO3 Pin 16 ADC1_CH5B */ ADC1_CH(11)
#define ADC_HW_VER_SENSE_CHANNEL /* GPIO_AD_22 GPIO3 Pin 21 ADC2_CH2A */ ADC2_CH(4)
#define ADC_HW_REV_SENSE_CHANNEL /* GPIO_AD_23 GPIO3 Pin 22 ADC2_CH2B */ ADC2_CH(5)
#define ADC_CHANNELS \
((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_ADC_6V6_CHANNEL) | \
(1 << ADC_ADC_3V3_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL))
// The ADC is used in SCALED mode.
// The V that is converted to a DN is 30/64 of Vin of the pin.
// The DN is therfore 30/64 of the real voltage
#define BOARD_ADC_POS_REF_V (1.825f * 64.0f / 30.0f)
#define HW_REV_VER_ADC_BASE IMXRT_LPADC2_BASE
#define SYSTEM_ADC_BASE IMXRT_LPADC1_BASE
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define HW_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_SLEW_FAST)
#define GPIO_HW_VER_REV_DRIVE /* GPIO_GPIO_EMC_B1_26 GPIO1_IO26 */ (GPIO_PORT1 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | HW_IOMUX)
#define GPIO_HW_REV_SENSE /* GPIO_AD_22 GPIO9 Pin 21 */ ADC_GPIO(4, 21)
#define GPIO_HW_VER_SENSE /* GPIO_AD_23 GPIO9 Pin 22 */ ADC_GPIO(5, 22)
#define HW_INFO_INIT_PREFIX "V6XRT"
#define V6XRT_00 HW_VER_REV(0x0,0x0) // First Release
#define BOARD_I2C_LATEINIT 1 /* See Note about SE550 Eanable */
/* HEATER
* PWM in future
*/
#define HEATER_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_SLEW_FAST)
//#define GPIO_HEATER_OUTPUT /* GPIO_EMC_B2_17 QTIMER3 TIMER0 GPIO2_IO27 */ (GPIO_QTIMER3_TIMER0_3 | HEATER_IOMUX)
#define GPIO_HEATER_OUTPUT /* GPIO_EMC_B2_17 GPIO2_IO27 */ (GPIO_PORT2 | GPIO_PIN27 | GPIO_OUTPUT | HEATER_IOMUX)
#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true))
/* nARMED GPIO1_IO17
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
* While armed it shall be configured at a GPIO OUT set LOW
*/
#define nARMED_INPUT_IOMUX (IOMUX_PULL_UP)
#define nARMED_OUTPUT_IOMUX (IOMUX_PULL_KEEP | IOMUX_SLEW_FAST)
#define GPIO_nARMED_INIT /* GPIO1_IO17 */ (GPIO_PORT1 | GPIO_PIN17 | GPIO_INPUT | nARMED_INPUT_IOMUX)
#define GPIO_nARMED /* GPIO1_IO17 */ (GPIO_PORT1 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | nARMED_OUTPUT_IOMUX)
#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT)
#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED)
/* PWM Capture
*
* 2 PWM Capture inputs are supported
*/
#define DIRECT_PWM_CAPTURE_CHANNELS 1
#define CAP_IOMUX (IOMUX_PULL_NONE | IOMUX_SLEW_FAST)
#define GPIO_FMU_CAP1 /* GPIO_EMC_B1_20 TMR4_TIMER0 */ (GPIO_QTIMER4_TIMER0_1 | CAP_IOMUX)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 12
#define BOARD_NUM_IO_TIMERS 12
// Input Capture not supported on MVP
#define BOARD_HAS_NO_CAPTURE
/* Power supply control and monitoring GPIOs */
#define GENERAL_INPUT_IOMUX (IOMUX_PULL_UP)
#define GENERAL_OUTPUT_IOMUX (IOMUX_PULL_KEEP | IOMUX_SLEW_FAST)
#define GPIO_nPOWER_IN_A /* GPIO_EMC_B1_28 GPIO1_IO28 */ (GPIO_PORT1 | GPIO_PIN28 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_B /* GPIO_EMC_B1_30 GPIO1_IO30 */ (GPIO_PORT1 | GPIO_PIN30 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_C /* GPIO_EMC_B1_32 GPIO2_IO00 */ (GPIO_PORT2 | GPIO_PIN0 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */
#define BOARD_NUMBER_BRICKS 2
#define BOARD_NUMBER_DIGITAL_BRICKS 2
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
#define OC_INPUT_IOMUX (IOMUX_PULL_NONE)
#define GPIO_VDD_5V_PERIPH_nEN /* GPIO_EMC_B1_34 GPIO2_IO02 */ (GPIO_PORT2 | GPIO_PIN2 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_5V_PERIPH_nOC /* GPIO_EMC_B1_15 GPIO1_IO15 */ (GPIO_PORT1 | GPIO_PIN15 | GPIO_INPUT | OC_INPUT_IOMUX)
#define GPIO_VDD_5V_HIPOWER_nEN /* GPIO_EMC_B1_37 GPIO2_IO05 */ (GPIO_PORT2 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_5V_HIPOWER_nOC /* GPIO_EMC_B1_12 GPIO1_IO12 */ (GPIO_PORT1 | GPIO_PIN12 | GPIO_INPUT | OC_INPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS1_EN /* GPIO_EMC_B1_33 GPIO2_IO01 */ (GPIO_PORT2 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS2_EN /* GPIO_EMC_B1_22 GPIO1_IO22 */ (GPIO_PORT1 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS3_EN /* GPIO_EMC_B1_14 GPIO1_IO14 */ (GPIO_PORT1 | GPIO_PIN14 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS4_EN /* GPIO_EMC_B1_36 GPIO2_IO04 */ (GPIO_PORT2 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* GPIO_EMC_B1_38 GPIO2_IO06 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SD_CARD_EN /* GPIO_EMC_B1_01 GPIO1_IO1 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO |GENERAL_OUTPUT_IOMUX)
/* ETHERNET GPIO */
#define GPIO_ETH_POWER_EN /* GPIO_DISP_B2_08 GPIO5_IO09 */ (GPIO_PORT5 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_ETH_PHY_nINT /* GPIO_DISP_B2_09 GPIO5_IO10 */ (GPIO_PORT5 | GPIO_PIN10 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_ENET2_RX_ER_CONFIG1 /* GPIO_DISP_B1_01 GPIO4_IO22 PHYAD18 Open */ (GPIO_PORT4 | GPIO_PIN22 | GPIO_INPUT | OC_INPUT_IOMUX | IOMUX_PULL_NONE)
#define GPIO_ENET2_RX_DATA01_CONFIG4 /* GPIO_EMC_B2_16 GPIO2_IO26 (RMII-Rev) Low */ (GPIO_PORT2 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_ENET2_RX_DATA00_CONFIG5 /* GPIO_EMC_B2_15 GPIO2_IO25 SLAVE:Auto Open */ (GPIO_PORT2 | GPIO_PIN25 | GPIO_INPUT | OC_INPUT_IOMUX | IOMUX_PULL_NONE)
#define GPIO_ENET2_CRS_DV_CONFIG6 /* GPIO_DISP_B1_00 GPIO4_IO21 SLAVE:POl Corr Low */ (GPIO_PORT4 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
/* NFC GPIO */
#define GPIO_NFC_GPIO /* GPIO_EMC_B1_04 GPIO1_IO04 */ (GPIO_PORT1 | GPIO_PIN4 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_GPIO_EMC_B2_12 /* GPIO_EMC_B2_12 AKA PD15, PH11 */ (GPIO_PORT2 | GPIO_PIN22 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
/* 10/100 Mbps Ethernet & Gigabit Ethernet */
/* 10/100 Mbps Ethernet Interrupt: GPIO_AD_12
* Gigabit Ethernet Interrupt: GPIO_DISP_B2_12
*
* This pin has a week pull-up within the PHY, is open-drain, and requires
* an external 1k ohm pull-up resistor (present on the EVK). A falling
* edge then indicates a change in state of the PHY.
*/
#define GPIO_ENET_INT (IOMUX_ENET_INT_DEFAULT | GPIO_OUTPUT | GPIO_PORT3 | GPIO_PIN11) /* GPIO_AD_12 */
#define GPIO_ENET_IRQ IMXRT_IRQ_GPIO3_0_15
#define GPIO_ENET1G_INT (IOMUX_ENET_INT_DEFAULT | GPIO_PORT5 | GPIO_PIN13) /* GPIO_DISP_B2_12 */
#define GPIO_ENET1G_IRQ IMXRT_IRQ_GPIO5_13
/* 10/100 Mbps Ethernet Reset: GPIO_LPSR_12
* Gigabit Ethernet Reset: GPIO_DISP_B2_13
*
* The #RST uses inverted logic. The initial value of zero will put the
* PHY into the reset state.
*/
#define GPIO_ENET_RST (GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GPIO_PORT6 | GPIO_PIN12 | IOMUX_ENET_RST_DEFAULT) /* GPIO_LPSR_12 */
#define GPIO_ENET1G_RST (GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GPIO_PORT5 | GPIO_PIN14 | IOMUX_ENET_RST_DEFAULT) /* GPIO_DISP_B2_13 */
/* Define True logic Power Control in arch agnostic form */
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true))
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true))
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true))
/* Tone alarm output */
#define TONE_ALARM_TIMER 3 /* GPT 3 */
#define TONE_ALARM_CHANNEL 2 /* GPIO_EMC_B2_09 GPT3_COMPARE2 */
#define GPIO_BUZZER_1 /* GPIO_EMC_B2_09 GPIO2_IO19 */ (GPIO_PORT2 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM (GPIO_GPT3_COMPARE2_1 | GENERAL_OUTPUT_IOMUX)
/* USB OTG FS
*
* VBUS_VALID is detected in USB_ANALOG_USB1_VBUS_DETECT_STAT
*/
/* High-resolution timer */
#define HRT_TIMER 5 /* use GPT5 for the HRT */
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 1 */
#define HRT_PPM_CHANNEL /* GPIO_EMC_B1_09 GPIO_GPT5_CAPTURE1_1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* GPIO_EMC_B1_09 GPT1_CAPTURE2 */ (GPIO_GPT5_CAPTURE1_1 | GENERAL_INPUT_IOMUX)
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
/* FLEXSPI4 */
#define GPIO_FLEXSPI2_CS (GPIO_FLEXSPI2_A_SS0_B_1|IOMUX_FLEXSPI_DEFAULT)
#define GPIO_FLEXSPI2_IO0 (GPIO_FLEXSPI2_A_DATA0_1|IOMUX_FLEXSPI_DEFAULT) /* SOUT */
#define GPIO_FLEXSPI2_IO1 (GPIO_FLEXSPI2_A_DATA1_1|IOMUX_FLEXSPI_DEFAULT) /* SIN */
#define GPIO_FLEXSPI2_SCK (GPIO_FLEXSPI2_A_SCLK_1|IOMUX_FLEXSPI_CLK_DEFAULT)
/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_B1_08 GPIO1_IO8 FLEXPWM2_PWM1_A */
#define PWMIN_TIMER /* FLEXPWM2_PWM1_A */ 2
#define PWMIN_TIMER_CHANNEL /* FLEXPWM2_PWM1_A */ 1
#define GPIO_PWM_IN /* GPIO_EMC_B1_08 GPIO1_IO8 */ (GPIO_FLEXPWM3_PWMA02_1 | GENERAL_INPUT_IOMUX)
/* Safety Switch is HW version dependent on having an PX4IO
* So we init to a benign state with the _INIT definition
* and provide the the non _INIT one for the driver to make a run time
* decision to use it.
*/
#define SAFETY_INIT_IOMUX (IOMUX_PULL_NONE )
#define SAFETY_IOMUX ( IOMUX_PULL_NONE | IOMUX_SLEW_SLOW)
#define SAFETY_SW_IOMUX ( IOMUX_PULL_UP )
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* GPIO_EMC_B1_03 GPIO1_IO03 */ (GPIO_PORT1 | GPIO_PIN3 | GPIO_INPUT | SAFETY_INIT_IOMUX)
#define GPIO_nSAFETY_SWITCH_LED_OUT /* GPIO_EMC_B1_03 GPIO1_IO03 */ (GPIO_PORT1 | GPIO_PIN3 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | SAFETY_IOMUX)
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
#define GPIO_SAFETY_SWITCH_IN /* GPIO_EMC_B1_24 GPIO1_IO24 */ (GPIO_PORT1 | GPIO_PIN24 | GPIO_INPUT | SAFETY_SW_IOMUX)
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
/* Power switch controls ******************************************************/
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
/*
* FMU-V6RT has a separate RC_IN and PPM
*
* GPIO PPM_IN on GPIO_EMC_B1_09 GPIO1 Pin 9 GPT5_CAPTURE1
* SPEKTRUM_RX (it's TX or RX in Bind) on TX UART6_TX_TO_IO__RC_INPUT GPIO_EMC_B1_40 GPIO2 Pin 8
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
*/
#define GPIO_UART_AS_OUT /* GPIO_EMC_B1_40 GPIO2_IO8 */ (GPIO_PORT2 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_UART_AS_OUT)
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_LPUART6_TX_1)
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_UART_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
*/
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0)
/* FMUv5 never powers odd the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C1_SCL_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C1_SDA_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C2_SCL_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C2_SDA_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C3_SCL_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C3_SDA_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C6_SCL_RESET), \
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_LPI2C6_SDA_RESET), \
GPIO_LPUART4_CTS_INIT , \
GPIO_LPUART8_CTS_INIT , \
GPIO_LPUART10_CTS_INIT, \
GPIO_nLED_RED, \
GPIO_nLED_GREEN, \
GPIO_nLED_BLUE, \
GPIO_BUZZER_1, \
GPIO_HW_VER_REV_DRIVE, \
GPIO_FLEXCAN1_TX, \
GPIO_FLEXCAN1_RX, \
GPIO_FLEXCAN2_TX, \
GPIO_FLEXCAN2_RX, \
GPIO_FLEXCAN3_TX, \
GPIO_FLEXCAN3_RX, \
GPIO_HEATER_OUTPUT, \
GPIO_FMU_CAP1, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
GPIO_nPOWER_IN_C, \
GPIO_VDD_5V_PERIPH_nEN, \
GPIO_VDD_5V_PERIPH_nOC, \
GPIO_VDD_5V_HIPOWER_nEN, \
GPIO_VDD_5V_HIPOWER_nOC, \
GPIO_VDD_3V3_SENSORS1_EN, \
GPIO_VDD_3V3_SENSORS2_EN, \
GPIO_VDD_3V3_SENSORS3_EN, \
GPIO_VDD_3V3_SENSORS4_EN, \
GPIO_VDD_3V3_SENSORS4_EN, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_SPIX_SYNC, \
GPIO_SPI6_nRESET_EXTERNAL1, \
GPIO_ETH_POWER_EN, \
GPIO_ETH_PHY_nINT, \
GPIO_GPIO_EMC_B2_12, \
GPIO_NFC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_PPM_IN, \
GPIO_nARMED_INIT, \
GPIO_ENET2_RX_ER_CONFIG1, \
GPIO_ENET2_RX_DATA01_CONFIG4, \
GPIO_ENET2_RX_DATA00_CONFIG5, \
GPIO_ENET2_CRS_DV_CONFIG6, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_I2C_BUS_MTD 1
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: fmuv6xrt_usdhc_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int fmuv6xrt_usdhc_initialize(void);
/************************************************************************************
* Name: imxrt_usb_initialize
*
* Description:
* Called to configure USB.
*
************************************************************************************/
extern int imxrt_usb_initialize(void);
/****************************************************************************************************
* Name: nxp_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
****************************************************************************************************/
extern void imxrt_spiinitialize(void);
extern void imxrt_usbinitialize(void);
extern void board_peripheral_reset(int ms);
extern void fmuv6xrt_timer_initialize(void);
#include <px4_platform_common/board_common.h>
int imxrt_flexspi_fram_initialize(void);
#endif /* __ASSEMBLY__ */
__END_DECLS
@@ -1,61 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file bootloader_main.c
*
* FMU-specific early startup code for bootloader
*/
#include "board_config.h"
#include "bl.h"
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <chip.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <px4_platform_common/init.h>
extern int sercon_main(int c, char **argv);
void board_late_initialize(void)
{
sercon_main(0, NULL);
}
extern void sys_tick_handler(void);
void board_timerhook(void)
{
sys_tick_handler();
}
-130
View File
@@ -1,130 +0,0 @@
/*
* hw_config.h
*
* Created on: May 17, 2015
* Author: david_s5
*/
#ifndef HW_CONFIG_H_
#define HW_CONFIG_H_
/****************************************************************************
* 10-8--2016:
* To simplify the ripple effect on the tools, we will be using
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
* moving forward all Bootloaders must contain the prefix "PX4 BL "
* in the USBDEVICESTRING
* This Change will be made in an upcoming BL release
****************************************************************************/
/*
* Define usage to configure a bootloader
*
*
* Constant example Usage
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
* BOARD_FMUV2
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
* USBPRODUCTID 0x0011 - PID Should match defconfig
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
* delay provided by an APP FW
* BOARD_TYPE 9 - Must match .prototype boad_id
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
* programmatically
*
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
* during a FW upgrade.
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
* flash_sectors table. Which is the second physical sector of FLASH in the device.
* The first physical sector of FLASH is used by the bootloader, and is not defined
* in the table.
*
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
* BOOTLOADER_RESERVATION_SIZE will be deducted from
* BOARD_FLASH_SIZE to determine the size of the App FW
* and hence the address space of FLASH to erase and program.
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
*
* * Other defines are somewhat self explanatory.
*/
/* Boot device selection list*/
#define USB0_DEV 0x01
#define SERIAL0_DEV 0x02
#define SERIAL1_DEV 0x04
#define APP_LOAD_ADDRESS 0x30020000
#define APP_VECTOR_OFFSET 0x2000
#define BOOTLOADER_DELAY 5000
#define INTERFACE_USB 1
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
//#define USE_VBUS_PULL_DOWN
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000"
#define BOOT_DELAY_ADDRESS 0x3003b540
#define BOARD_TYPE 35
// The board has a 64 Mb part with 16384, 4K secors, but we artificialy limit it to 4 Mb
// as 1024, 4K sectors
#define BOARD_FLASH_SECTORS 1024 // Really (16384)
#define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 32 // We resreve 128K for the bootloader
#define BOARD_FLASH_SIZE (4 * 1024 * 1024)
#define OSC_FREQ 24
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN
#define BOARD_LED_ON 0
#define BOARD_LED_OFF 1
#define SERIAL_BREAK_DETECT_DISABLED 1
/*
* Uncommenting this allows to force the bootloader through
* a PWM output pin. As this can accidentally initialize
* an ESC prematurely, it is not recommended. This feature
* has not been used and hence defaults now to off.
*
* # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14)
* # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
*
* # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
* # define BOARD_POWER_ON 1
* # define BOARD_POWER_OFF 0
* # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power)
*
*/
#if !defined(ARCH_SN_MAX_LENGTH)
# define ARCH_SN_MAX_LENGTH 12
#endif
#if !defined(APP_RESERVATION_SIZE)
# define APP_RESERVATION_SIZE 0
#endif
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
#endif
#if !defined(USB_DATA_ALIGN)
# define USB_DATA_ALIGN
#endif
#ifndef BOOT_DEVICES_SELECTION
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
#ifndef BOOT_DEVICES_FILTER_ONUSB
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
#endif /* HW_CONFIG_H_ */
@@ -1,510 +0,0 @@
/****************************************************************************
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_clockconfig.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/* Copyright 2022 NXP */
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include "imxrt_clockconfig.h"
/****************************************************************************
* Public Data
****************************************************************************/
/* Each FMU-V6XRT board must provide the following initialized structure.
* This is needed to establish the initial board clocking.
*/
const struct clock_configuration_s g_initial_clkconfig = {
.ccm =
{
.m7_clk_root =
{
.enable = 1,
.div = 1,
.mux = M7_CLK_ROOT_PLL_ARM_CLK,
},
.m4_clk_root =
{
.enable = 1,
.div = 1,
.mux = M4_CLK_ROOT_SYS_PLL3_PFD3,
},
.bus_clk_root =
{
.enable = 1,
.div = 2,
.mux = BUS_CLK_ROOT_SYS_PLL3_CLK,
},
.bus_lpsr_clk_root =
{
.enable = 1,
.div = 3,
.mux = BUS_LPSR_CLK_ROOT_SYS_PLL3_CLK,
},
.semc_clk_root =
{
.enable = 0,
.div = 3,
.mux = SEMC_CLK_ROOT_SYS_PLL2_PFD1,
},
.cssys_clk_root =
{
.enable = 1,
.div = 1,
.mux = CSSYS_CLK_ROOT_OSC_RC_48M_DIV2,
},
.cstrace_clk_root =
{
.enable = 1,
.div = 4,
.mux = CSTRACE_CLK_ROOT_SYS_PLL2_CLK,
},
.m4_systick_clk_root =
{
.enable = 1,
.div = 1,
.mux = M4_SYSTICK_CLK_ROOT_OSC_RC_48M_DIV2,
},
.m7_systick_clk_root =
{
.enable = 1,
.div = 240,
.mux = M7_SYSTICK_CLK_ROOT_OSC_RC_48M_DIV2,
},
.adc1_clk_root =
{
.enable = 1,
.div = 6,
.mux = ADC1_CLK_ROOT_SYS_PLL2_CLK,
},
.adc2_clk_root =
{
.enable = 1,
.div = 6,
.mux = ADC2_CLK_ROOT_SYS_PLL2_CLK,
},
.acmp_clk_root =
{
.enable = 1,
.div = 1,
.mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2,
},
.flexio1_clk_root =
{
.enable = 1,
.div = 1,
.mux = FLEXIO1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.flexio2_clk_root =
{
.enable = 1,
.div = 1,
.mux = FLEXIO2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.gpt1_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.gpt2_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.gpt3_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT3_CLK_ROOT_OSC_24M,
},
.gpt4_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT4_CLK_ROOT_OSC_RC_48M_DIV2,
},
.gpt5_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT5_CLK_ROOT_OSC_24M,
},
.gpt6_clk_root =
{
.enable = 1,
.div = 1,
.mux = GPT6_CLK_ROOT_OSC_RC_48M_DIV2,
},
.flexspi1_clk_root =
{
.enable = 1,
.div = 4,
.mux = FLEXSPI1_CLK_ROOT_SYS_PLL2_CLK,
},
.flexspi2_clk_root =
{
.enable = 1,
.div = 1,
.mux = FLEXSPI2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.can1_clk_root = /* 240 / 3 = 80Mhz */
{
.enable = 1,
.div = 3,
.mux = CAN1_CLK_ROOT_SYS_PLL3_DIV2,
},
.can2_clk_root = /* 240 / 3 = 80Mhz */
{
.enable = 1,
.div = 3,
.mux = CAN2_CLK_ROOT_SYS_PLL3_DIV2,
},
.can3_clk_root = /* 480 / 6 = 80Mhz */
{
.enable = 1,
.div = 6,
.mux = CAN3_CLK_ROOT_SYS_PLL3_CLK,
},
.lpuart1_clk_root = /* 528 / 22 = 24Mhz */
{
.enable = 1,
.div = 22,
.mux = LPUART1_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart3_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART3_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart4_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART4_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart5_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART5_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart6_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART6_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart8_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART8_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart10_clk_root = /* 528 / 11 = 48Mhz */
{
.enable = 1,
.div = 11,
.mux = LPUART10_CLK_ROOT_SYS_PLL2_CLK,
},
.lpuart11_clk_root = /* 480 / 10 = 48Mhz */
{
.enable = 1,
.div = 10,
.mux = LPUART11_CLK_ROOT_SYS_PLL3_CLK,
},
.lpi2c1_clk_root = /* 528 / 22 = 24Mhz */
{
.enable = 1,
.div = 22,
.mux = LPI2C1_CLK_ROOT_SYS_PLL2_CLK,
},
.lpi2c2_clk_root = /* 528 / 22 = 24Mhz */
{
.enable = 1,
.div = 22,
.mux = LPI2C2_CLK_ROOT_SYS_PLL2_CLK,
},
.lpi2c3_clk_root = /* 528 / 22 = 24Mhz */
{
.enable = 1,
.div = 22,
.mux = LPI2C3_CLK_ROOT_SYS_PLL2_CLK,
},
.lpi2c6_clk_root = /* 480 / 20 = 24Mhz */
{
.enable = 1,
.div = 20,
.mux = LPI2C6_CLK_ROOT_SYS_PLL3_CLK,
},
.lpspi1_clk_root = /* 200 / 2 = 100Mhz */
{
.enable = 1,
.div = 2,
.mux = LPSPI1_CLK_ROOT_SYS_PLL1_DIV5,
},
.lpspi2_clk_root = /* 200 / 2 = 100Mhz */
{
.enable = 1,
.div = 2,
.mux = LPSPI2_CLK_ROOT_SYS_PLL1_DIV5,
},
.lpspi3_clk_root = /* 200 / 2 = 100Mhz */
{
.enable = 1,
.div = 2,
.mux = LPSPI3_CLK_ROOT_SYS_PLL1_DIV5,
},
.lpspi6_clk_root = /* 200 / 2 = 100Mhz */
{
.enable = 1,
.div = 2,
.mux = LPSPI6_CLK_ROOT_SYS_PLL1_DIV5,
},
.emv1_clk_root =
{
.enable = 0,
.div = 1,
.mux = EMV1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.emv2_clk_root =
{
.enable = 0,
.div = 1,
.mux = EMV2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.enet1_clk_root =
{
.enable = 0,
.div = 10,
.mux = ENET1_CLK_ROOT_SYS_PLL1_DIV2,
},
.enet2_clk_root =
{
.enable = 0,
.div = 10,
.mux = ENET2_CLK_ROOT_SYS_PLL1_DIV2,
},
.enet_qos_clk_root =
{
.enable = 0,
.div = 1,
.mux = ENET_QOS_CLK_ROOT_OSC_RC_48M_DIV2,
},
.enet_25m_clk_root =
{
.enable = 1,
.div = 1,
.mux = ENET_25M_CLK_ROOT_OSC_RC_48M_DIV2,
},
.enet_timer1_clk_root =
{
.enable = 0,
.div = 1,
.mux = ENET_TIMER1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.enet_timer2_clk_root =
{
.enable = 0,
.div = 1,
.mux = ENET_TIMER2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.enet_timer3_clk_root =
{
.enable = 0,
.div = 1,
.mux = ENET_TIMER3_CLK_ROOT_OSC_RC_48M_DIV2,
},
.usdhc1_clk_root =
{
.enable = 1,
.div = 2,
.mux = USDHC1_CLK_ROOT_SYS_PLL2_PFD2,
},
.usdhc2_clk_root =
{
.enable = 0,
.div = 1,
.mux = USDHC2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.asrc_clk_root =
{
.enable = 0,
.div = 1,
.mux = ASRC_CLK_ROOT_OSC_RC_48M_DIV2,
},
.mqs_clk_root =
{
.enable = 0,
.div = 1,
.mux = MQS_CLK_ROOT_OSC_RC_48M_DIV2,
},
.mic_clk_root =
{
.enable = 0,
.div = 1,
.mux = MIC_CLK_ROOT_OSC_RC_48M_DIV2,
},
.spdif_clk_root =
{
.enable = 0,
.div = 1,
.mux = SPDIF_CLK_ROOT_OSC_RC_48M_DIV2,
},
.sai1_clk_root =
{
.enable = 0,
.div = 1,
.mux = SAI1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.sai2_clk_root =
{
.enable = 0,
.div = 1,
.mux = SAI2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.sai3_clk_root =
{
.enable = 0,
.div = 1,
.mux = SAI3_CLK_ROOT_OSC_RC_48M_DIV2,
},
.sai4_clk_root =
{
.enable = 0,
.div = 1,
.mux = SAI4_CLK_ROOT_OSC_RC_48M_DIV2,
},
.gc355_clk_root =
{
.enable = 0,
.div = 2,
.mux = GC355_CLK_ROOT_VIDEO_PLL_CLK,
},
.lcdif_clk_root =
{
.enable = 0,
.div = 1,
.mux = LCDIF_CLK_ROOT_OSC_RC_48M_DIV2,
},
.lcdifv2_clk_root =
{
.enable = 0,
.div = 1,
.mux = LCDIFV2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.mipi_ref_clk_root =
{
.enable = 0,
.div = 1,
.mux = MIPI_REF_CLK_ROOT_OSC_RC_48M_DIV2,
},
.mipi_esc_clk_root =
{
.enable = 0,
.div = 1,
.mux = MIPI_ESC_CLK_ROOT_OSC_RC_48M_DIV2,
},
.csi2_clk_root =
{
.enable = 0,
.div = 1,
.mux = CSI2_CLK_ROOT_OSC_RC_48M_DIV2,
},
.csi2_esc_clk_root =
{
.enable = 0,
.div = 1,
.mux = CSI2_ESC_CLK_ROOT_OSC_RC_48M_DIV2,
},
.csi2_ui_clk_root =
{
.enable = 0,
.div = 1,
.mux = CSI2_UI_CLK_ROOT_OSC_RC_48M_DIV2,
},
.csi_clk_root =
{
.enable = 0,
.div = 1,
.mux = CSI_CLK_ROOT_OSC_RC_48M_DIV2,
},
.cko1_clk_root =
{
.enable = 0,
.div = 1,
.mux = CKO1_CLK_ROOT_OSC_RC_48M_DIV2,
},
.cko2_clk_root =
{
.enable = 0,
.div = 1,
.mux = CKO2_CLK_ROOT_OSC_RC_48M_DIV2,
},
},
.arm_pll =
{
/* ARM_PLL = Fin * ( loop_div / ( 2 * post_div ) ) */
/* ARM_PLL = Fin * ( 166 / ( 2 * 2 ) ) */
.post_div = 0, /* 0 = DIV by 2
* 1 = DIV by 4
* 2 = DIV by 8
* 3 = DIV by 1 */
.loop_div = 166, /* ARM_PLL = 996 Mhz */
},
.sys_pll1 =
{
.enable = 1,
.div = 41,
.num = 178956970,
.denom = 268435455,
},
.sys_pll2 =
{
.mfd = 268435455,
.ss_enable = 0,
.pfd0 = 27, /* (528 * 18) / 27 = 352 MHz */
.pfd1 = 16, /* (528 * 16) / 16 = 594 MHz */
.pfd2 = 24, /* (528 * 24) / 27 = 396 MHz */
.pfd3 = 32, /* (528 * 32) / 27 = 297 MHz */
},
.sys_pll3 =
{
.pfd0 = 13, /* (480 * 18) / 13 = 8640/13 = 664.62 MHz */
.pfd1 = 17, /* (480 * 18) / 17 = 8640/17 = 508.24 MHz */
.pfd2 = 32, /* (480 * 18) / 32 = 270 MHz */
.pfd3 = 22, /* (480 * 18) / 22 = 8640/20 = 392.73 MHz */
}
};
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -1,695 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_flexspi_fram.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <nuttx/fs/fs.h>
#include <nuttx/mtd/mtd.h>
#include <px4_platform_common/px4_mtd.h>
#include "px4_log.h"
#include "imxrt_flexspi.h"
#include "board_config.h"
#include "hardware/imxrt_pinmux.h"
#ifdef CONFIG_IMXRT_FLEXSPI
#define FRAM_SIZE 0x8000U
#define FRAM_PAGE_SIZE 0x0080U
#define FRAM_SECTOR_SIZE 0x0080U
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
enum {
/* SPI instructions */
READ_ID,
READ_STATUS_REG,
WRITE_STATUS_REG,
WRITE_ENABLE,
READ_FAST,
PAGE_PROGRAM,
};
static const uint32_t g_flexspi_fram_lut[][4] = {
[READ_ID] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x9f,
FLEXSPI_COMMAND_READ_SDR, FLEXSPI_1PAD, 0x04),
},
[READ_STATUS_REG] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x05,
FLEXSPI_COMMAND_READ_SDR, FLEXSPI_1PAD, 0x04),
},
[WRITE_STATUS_REG] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x01,
FLEXSPI_COMMAND_WRITE_SDR, FLEXSPI_1PAD, 0x04),
},
[WRITE_ENABLE] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x06,
FLEXSPI_COMMAND_STOP, FLEXSPI_1PAD, 0),
},
[READ_FAST] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x0b,
FLEXSPI_COMMAND_RADDR_SDR, FLEXSPI_1PAD, 0x10),
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_DUMMY_SDR, FLEXSPI_1PAD, 0x08,
FLEXSPI_COMMAND_READ_SDR, FLEXSPI_1PAD, 0x04),
},
[PAGE_PROGRAM] =
{
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_SDR, FLEXSPI_1PAD, 0x02,
FLEXSPI_COMMAND_RADDR_SDR, FLEXSPI_1PAD, 0x10),
FLEXSPI_LUT_SEQ(FLEXSPI_COMMAND_WRITE_SDR, FLEXSPI_1PAD, 0x04,
FLEXSPI_COMMAND_STOP, FLEXSPI_1PAD, 0),
},
};
/****************************************************************************
* Private Types
****************************************************************************/
/* FlexSPI NOR device private data */
struct imxrt_flexspi_fram_dev_s {
struct mtd_dev_s mtd;
struct flexspi_dev_s *flexspi; /* Saved FlexSPI interface instance */
uint8_t *ahb_base;
enum flexspi_port_e port;
struct flexspi_device_config_s *config;
};
/****************************************************************************
* Private Functions Prototypes
****************************************************************************/
/* MTD driver methods */
static int imxrt_flexspi_fram_erase(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks);
static ssize_t imxrt_flexspi_fram_read(struct mtd_dev_s *dev,
off_t offset,
size_t nbytes,
uint8_t *buffer);
static ssize_t imxrt_flexspi_fram_bread(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks,
uint8_t *buffer);
static ssize_t imxrt_flexspi_fram_bwrite(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks,
const uint8_t *buffer);
static int imxrt_flexspi_fram_ioctl(struct mtd_dev_s *dev,
int cmd,
unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static struct flexspi_device_config_s g_flexspi_device_config = {
.flexspi_root_clk = 4000000,
.is_sck2_enabled = 0,
.flash_size = 32,
.cs_interval_unit = FLEXSPI_CS_INTERVAL_UNIT1_SCK_CYCLE,
.cs_interval = 0,
.cs_hold_time = 12,
.cs_setup_time = 12,
.data_valid_time = 0,
.columnspace = 0,
.enable_word_address = 0,
.awr_seq_index = 0,
.awr_seq_number = 0,
.ard_seq_index = READ_FAST,
.ard_seq_number = 1,
.ahb_write_wait_unit = FLEXSPI_AHB_WRITE_WAIT_UNIT2_AHB_CYCLE,
.ahb_write_wait_interval = 0,
.rx_sample_clock = FLEXSPI_READ_SAMPLE_CLK_LOOPBACK_INTERNALLY,
};
static struct imxrt_flexspi_fram_dev_s g_flexspi_nor = {
.mtd =
{
.erase = imxrt_flexspi_fram_erase,
.bread = imxrt_flexspi_fram_bread,
.bwrite = imxrt_flexspi_fram_bwrite,
.read = imxrt_flexspi_fram_read,
.ioctl = imxrt_flexspi_fram_ioctl,
#ifdef CONFIG_MTD_BYTE_WRITE
.write = NULL,
#endif
.name = "imxrt_flexspi_fram"
},
.flexspi = (void *)0,
.ahb_base = (uint8_t *) IMXRT_FLEXSPI2_CIPHER_BASE,
.port = FLEXSPI_PORT_A1,
.config = &g_flexspi_device_config
};
/****************************************************************************
* Private Functions
****************************************************************************/
static int imxrt_flexspi_fram_get_vendor_id(
const struct imxrt_flexspi_fram_dev_s *dev,
uint8_t *vendor_id)
{
uint8_t buffer[1] = {0};
int stat;
struct flexspi_transfer_s transfer = {
.device_address = 0,
.port = dev->port,
.cmd_type = FLEXSPI_READ,
.seq_number = 1,
.seq_index = READ_ID,
.data = (void *) &buffer,
.data_size = 1,
};
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
*vendor_id = buffer[0];
return 0;
}
static int imxrt_flexspi_fram_read_status(
const struct imxrt_flexspi_fram_dev_s *dev,
uint32_t *status)
{
int stat;
struct flexspi_transfer_s transfer = {
.device_address = 0,
.port = dev->port,
.cmd_type = FLEXSPI_READ,
.seq_number = 1,
.seq_index = READ_STATUS_REG,
.data = status,
.data_size = 1,
};
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
return 0;
}
#if 0
static int imxrt_flexspi_fram_write_status(
const struct imxrt_flexspi_fram_dev_s *dev,
uint32_t *status)
{
int stat;
struct flexspi_transfer_s transfer = {
.device_address = 0,
.port = dev->port,
.cmd_type = FLEXSPI_WRITE,
.seq_number = 1,
.seq_index = WRITE_STATUS_REG,
.data = status,
.data_size = 1,
};
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
return 0;
}
#endif
static int imxrt_flexspi_fram_write_enable(
const struct imxrt_flexspi_fram_dev_s *dev)
{
int stat;
struct flexspi_transfer_s transfer = {
.device_address = 0,
.port = dev->port,
.cmd_type = FLEXSPI_COMMAND,
.seq_number = 1,
.seq_index = WRITE_ENABLE,
.data = NULL,
.data_size = 0,
};
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
return 0;
}
static int imxrt_flexspi_fram_erase_sector(
const struct imxrt_flexspi_fram_dev_s *dev,
off_t offset)
{
int stat;
size_t remaining = FRAM_SECTOR_SIZE;
uint8_t buffer[FRAM_SECTOR_SIZE] = {0xff};
struct flexspi_transfer_s transfer = {
.data = (void *) &buffer,
.port = dev->port,
.cmd_type = FLEXSPI_WRITE,
.seq_number = 1,
.seq_index = PAGE_PROGRAM,
};
while (remaining > 0) {
transfer.device_address = offset;
transfer.data_size = MIN(128, remaining);
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
remaining -= transfer.data_size;
offset += transfer.data_size;
}
return 0;
}
static int imxrt_flexspi_fram_erase_chip(
const struct imxrt_flexspi_fram_dev_s *dev)
{
int stat;
size_t remaining = FRAM_SIZE;
size_t offset = 0;
uint8_t buffer[FRAM_SECTOR_SIZE] = {0xff};
struct flexspi_transfer_s transfer = {
.data = (void *) &buffer,
.port = dev->port,
.cmd_type = FLEXSPI_WRITE,
.seq_number = 1,
.seq_index = PAGE_PROGRAM,
};
while (remaining > 0) {
transfer.device_address = offset;
transfer.data_size = MIN(128, remaining);
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
remaining -= transfer.data_size;
offset += transfer.data_size;
}
return 0;
}
static int imxrt_flexspi_fram_page_program(
const struct imxrt_flexspi_fram_dev_s *dev,
off_t offset,
const void *buffer,
size_t len)
{
int stat;
struct flexspi_transfer_s transfer = {
.device_address = offset,
.port = dev->port,
.cmd_type = FLEXSPI_WRITE,
.seq_number = 1,
.seq_index = PAGE_PROGRAM,
.data = (uint32_t *) buffer,
.data_size = len,
};
stat = FLEXSPI_TRANSFER(dev->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
return 0;
}
static int imxrt_flexspi_fram_wait_bus_busy(
const struct imxrt_flexspi_fram_dev_s *dev)
{
uint32_t status = 0;
int ret;
do {
ret = imxrt_flexspi_fram_read_status(dev, &status);
if (ret) {
return ret;
}
} while (status & 1);
return 0;
}
static ssize_t imxrt_flexspi_fram_read(struct mtd_dev_s *dev,
off_t offset,
size_t nbytes,
uint8_t *buffer)
{
#ifdef IP_READ
struct imxrt_flexspi_fram_dev_s *priv =
(struct imxrt_flexspi_fram_dev_s *)dev;
int stat;
size_t remaining = nbytes;
struct flexspi_transfer_s transfer = {
.port = priv->port,
.cmd_type = FLEXSPI_READ,
.seq_number = 1,
.seq_index = READ_FAST,
};
while (remaining > 0) {
transfer.device_address = offset;
transfer.data = buffer;
transfer.data_size = MIN(128, remaining);
stat = FLEXSPI_TRANSFER(priv->flexspi, &transfer);
if (stat != 0) {
return -EIO;
}
remaining -= transfer.data_size;
buffer += transfer.data_size;
offset += transfer.data_size;
}
return 0;
#else
struct imxrt_flexspi_fram_dev_s *priv =
(struct imxrt_flexspi_fram_dev_s *)dev;
uint8_t *src;
finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes);
if (priv->port >= FLEXSPI_PORT_COUNT) {
return -EIO;
}
src = priv->ahb_base + offset;
memcpy(buffer, src, nbytes);
finfo("return nbytes: %d\n", (int)nbytes);
return (ssize_t)nbytes;
#endif
}
static ssize_t imxrt_flexspi_fram_bread(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks,
uint8_t *buffer)
{
ssize_t nbytes;
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
/* On this device, we can handle the block read just like the byte-oriented
* read
*/
nbytes = imxrt_flexspi_fram_read(dev, startblock * FRAM_PAGE_SIZE,
nblocks * FRAM_PAGE_SIZE, buffer);
if (nbytes > 0) {
nbytes /= FRAM_PAGE_SIZE;
}
return nbytes;
}
static ssize_t imxrt_flexspi_fram_bwrite(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks,
const uint8_t *buffer)
{
struct imxrt_flexspi_fram_dev_s *priv =
(struct imxrt_flexspi_fram_dev_s *)dev;
size_t len = nblocks * FRAM_PAGE_SIZE;
off_t offset = startblock * FRAM_PAGE_SIZE;
uint8_t *src = (uint8_t *) buffer;
#ifdef CONFIG_ARMV7M_DCACHE
uint8_t *dst = priv->ahb_base + startblock * FRAM_PAGE_SIZE;
#endif
int i;
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
while (len) {
i = MIN(FRAM_PAGE_SIZE, len);
imxrt_flexspi_fram_write_enable(priv);
imxrt_flexspi_fram_page_program(priv, offset, src, i);
imxrt_flexspi_fram_wait_bus_busy(priv);
FLEXSPI_SOFTWARE_RESET(priv->flexspi);
offset += i;
len -= i;
}
#ifdef CONFIG_ARMV7M_DCACHE
up_invalidate_dcache((uintptr_t)dst,
(uintptr_t)dst + nblocks * FRAM_PAGE_SIZE);
#endif
return nblocks;
}
static int imxrt_flexspi_fram_erase(struct mtd_dev_s *dev,
off_t startblock,
size_t nblocks)
{
struct imxrt_flexspi_fram_dev_s *priv =
(struct imxrt_flexspi_fram_dev_s *)dev;
size_t blocksleft = nblocks;
#ifdef CONFIG_ARMV7M_DCACHE
uint8_t *dst = priv->ahb_base + startblock * FRAM_SECTOR_SIZE;
#endif
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
while (blocksleft-- > 0) {
/* Erase each sector */
imxrt_flexspi_fram_write_enable(priv);
imxrt_flexspi_fram_erase_sector(priv, startblock * FRAM_SECTOR_SIZE);
imxrt_flexspi_fram_wait_bus_busy(priv);
FLEXSPI_SOFTWARE_RESET(priv->flexspi);
startblock++;
}
#ifdef CONFIG_ARMV7M_DCACHE
up_invalidate_dcache((uintptr_t)dst,
(uintptr_t)dst + nblocks * FRAM_SECTOR_SIZE);
#endif
return (int)nblocks;
}
static int imxrt_flexspi_fram_ioctl(struct mtd_dev_s *dev,
int cmd,
unsigned long arg)
{
struct imxrt_flexspi_fram_dev_s *priv =
(struct imxrt_flexspi_fram_dev_s *)dev;
int ret = -EINVAL; /* Assume good command with bad parameters */
finfo("cmd: %d\n", cmd);
switch (cmd) {
case MTDIOC_GEOMETRY: {
struct mtd_geometry_s *geo =
(struct mtd_geometry_s *)((uintptr_t)arg);
if (geo) {
/* Populate the geometry structure with information need to
* know the capacity and how to access the device.
*
* NOTE:
* that the device is treated as though it where just an array
* of fixed size blocks. That is most likely not true, but the
* client will expect the device logic to do whatever is
* necessary to make it appear so.
*/
geo->blocksize = (FRAM_PAGE_SIZE);
geo->erasesize = (FRAM_SECTOR_SIZE);
geo->neraseblocks = (FRAM_SIZE / FRAM_SECTOR_SIZE);
ret = OK;
finfo("blocksize: %lu erasesize: %lu neraseblocks: %lu\n",
geo->blocksize, geo->erasesize, geo->neraseblocks);
}
}
break;
case BIOC_PARTINFO: {
struct partition_info_s *info =
(struct partition_info_s *)arg;
if (info != NULL) {
info->numsectors = (FRAM_SIZE / FRAM_SECTOR_SIZE);
info->sectorsize = FRAM_PAGE_SIZE;
info->startsector = 0;
info->parent[0] = '\0';
ret = OK;
}
}
break;
case MTDIOC_BULKERASE: {
/* Erase the entire device */
imxrt_flexspi_fram_write_enable(priv);
imxrt_flexspi_fram_erase_chip(priv);
imxrt_flexspi_fram_wait_bus_busy(priv);
FLEXSPI_SOFTWARE_RESET(priv->flexspi);
ret = OK;
}
break;
case MTDIOC_PROTECT:
/* TODO */
break;
case MTDIOC_UNPROTECT:
/* TODO */
break;
default:
ret = -ENOTTY; /* Bad/unsupported command */
break;
}
finfo("return %d\n", ret);
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
int flexspi_attach(mtd_instance_s *instance)
{
int rv = imxrt_flexspi_fram_initialize();
if (rv != OK) {
PX4_ERR("failed to initalize flexspi bus");
return -ENXIO;
}
instance->mtd_dev = &g_flexspi_nor.mtd;
return OK;
}
/****************************************************************************
* Name: imxrt_flexspi_fram_initialize
*
* Description:
* This function is called by board-bringup logic to configure the
* flash device.
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
* returned to indicate the nature of the failure.
*
****************************************************************************/
int imxrt_flexspi_fram_initialize(void)
{
uint8_t vendor_id;
int ret = -ENODEV;
/* Configure multiplexed pins as connected on the board */
imxrt_config_gpio(GPIO_FLEXSPI2_CS);
imxrt_config_gpio(GPIO_FLEXSPI2_IO0);
imxrt_config_gpio(GPIO_FLEXSPI2_IO1);
imxrt_config_gpio(GPIO_FLEXSPI2_SCK);
/* Select FlexSPI2 */
g_flexspi_nor.flexspi = imxrt_flexspi_initialize(1);
if (g_flexspi_nor.flexspi) {
FLEXSPI_SET_DEVICE_CONFIG(g_flexspi_nor.flexspi,
g_flexspi_nor.config,
g_flexspi_nor.port);
FLEXSPI_UPDATE_LUT(g_flexspi_nor.flexspi,
0,
(const uint32_t *)g_flexspi_fram_lut,
sizeof(g_flexspi_fram_lut) / 4);
FLEXSPI_SOFTWARE_RESET(g_flexspi_nor.flexspi);
ret = OK;
if (imxrt_flexspi_fram_get_vendor_id(&g_flexspi_nor, &vendor_id)) {
ret = -EIO;
}
}
return ret;
}
#endif /* CONFIG_IMXRT_FLEXSPI */
@@ -1,49 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_boot.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include "imxrt_flexspi_nor_boot.h"
/****************************************************************************
* Public Data
****************************************************************************/
locate_data(".boot_hdr.ivt")
const struct ivt_s g_image_vector_table = {
IVT_HEADER, /* IVT Header */
IMAGE_ENTRY_ADDRESS, /* Image Entry Function */
IVT_RSVD, /* Reserved = 0 */
(uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */
(uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */
(uint32_t)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */
(uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */
IVT_RSVD /* Reserved = 0 */
};
locate_data(".boot_hdr.boot_data")
const struct boot_data_s g_boot_data = {
IMAGE_DEST, /* boot start location */
(IMAGE_DEST_END - IMAGE_DEST), /* size */
PLUGIN_FLAG, /* Plugin flag */
0xffffffff /* empty - extra data word */
};
@@ -1,144 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include "imxrt_flexspi_nor_flash.h"
/****************************************************************************
* Public Data
****************************************************************************/
locate_data(".boot_hdr.conf")
const struct flexspi_nor_config_s g_flash_config = {
.memConfig =
{
#if !defined(CONFIG_BOARD_BOOTLOADER_INVALID_FCB)
.tag = FLEXSPI_CFG_BLK_TAG,
#else
.tag = 0xffffffffL,
#endif
.version = FLEXSPI_CFG_BLK_VERSION,
.readSampleClkSrc = kFlexSPIReadSampleClk_LoopbackInternally,
.csHoldTime = 1,
.csSetupTime = 1,
.deviceModeCfgEnable = 1,
.deviceModeType = kDeviceConfigCmdType_Generic,
.waitTimeCfgCommands = 1,
.controllerMiscOption =
(1u << kFlexSpiMiscOffset_SafeConfigFreqEnable),
.deviceType = kFlexSpiDeviceType_SerialNOR,
.sflashPadType = kSerialFlash_1Pad,
.serialClkFreq = kFlexSpiSerialClk_30MHz,
.sflashA1Size = 64ul * 1024u * 1024u,
.dataValidTime =
{
[0] = {.time_100ps = 0},
},
.busyOffset = 0u,
.busyBitPolarity = 0u,
.lookupTable =
{
/* Read Dedicated 3Byte Address Read(0x03), 24bit address */
[0 + 0] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x03, RADDR_SDR, FLEXSPI_1PAD, 0x18), //0x871187ee,
[0 + 1] = FLEXSPI_LUT_SEQ(READ_SDR, FLEXSPI_1PAD, 0x04, STOP_EXE, FLEXSPI_1PAD, 0),//0xb3048b20
},
},
.pageSize = 256u,
.sectorSize = 4u * 1024u,
.blockSize = 64u * 1024u,
.isUniformBlockSize = false,
.ipcmdSerialClkFreq = 1,
.serialNorType = 2,
.reserve2[0] = 0x7008200,
};
const struct flexspi_nor_config_s g_flash_fast_config = {
.memConfig =
{
.tag = FLEXSPI_CFG_BLK_TAG,
.version = FLEXSPI_CFG_BLK_VERSION,
.readSampleClkSrc = kFlexSPIReadSampleClk_ExternalInputFromDqsPad,
.csHoldTime = 1,
.csSetupTime = 1,
.deviceModeCfgEnable = 1,
.deviceModeType = kDeviceConfigCmdType_Spi2Xpi,
.waitTimeCfgCommands = 1,
.deviceModeSeq =
{
.seqNum = 1,
.seqId = 6, /* See Lookup table for more details */
.reserved = 0,
},
.deviceModeArg = 2, /* Enable OPI DDR mode */
.controllerMiscOption =
(1u << kFlexSpiMiscOffset_SafeConfigFreqEnable) | (1u << kFlexSpiMiscOffset_DdrModeEnable),
.deviceType = kFlexSpiDeviceType_SerialNOR,
.sflashPadType = kSerialFlash_8Pads,
.serialClkFreq = kFlexSpiSerialClk_200MHz,
.sflashA1Size = 64ul * 1024u * 1024u,
.dataValidTime =
{
[0] = {.time_100ps = 0},
},
.busyOffset = 0u,
.busyBitPolarity = 0u,
.lookupTable =
{
/* Read */// EEH+11H+32bit addr+20dummy cycles+ 4Bytes read data //200Mhz 18 dummy=10+8
[0 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xEE, CMD_DDR, FLEXSPI_8PAD, 0x11), //0x871187ee,
[0 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x04),//0xb3048b20,
[0 + 2] = FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP_EXE, FLEXSPI_1PAD, 0x00), //0xa704,
/* Read status */
[4 * 2 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0x05, CMD_DDR, FLEXSPI_8PAD, 0xfa),
[4 * 2 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x04),
[4 * 2 + 2] = FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP_EXE, FLEXSPI_1PAD, 0x00),
/* Write enable SPI *///06h
[4 * 3 + 0] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06, STOP_EXE, FLEXSPI_1PAD, 0x00),//0x00000406,
/* Write enable OPI SPI *///06h
[4 * 4 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0x06, CMD_DDR, FLEXSPI_8PAD, 0xF9),
/* Erase sector */
[4 * 5 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0x21, CMD_DDR, FLEXSPI_8PAD, 0xDE),
[4 * 5 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, STOP_EXE, FLEXSPI_1PAD, 0x00),
/*Write Configuration Register 2 =01, Enable OPI DDR mode*/ //72H +32bit address + CR20x00000000 = 0x01
[4 * 6 + 0] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x72, CMD_SDR, FLEXSPI_1PAD, 0x00),//0x04000472,
[4 * 6 + 1] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x00, CMD_SDR, FLEXSPI_1PAD, 0x00),//0x04000400,
[4 * 6 + 2] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x00, WRITE_SDR, FLEXSPI_1PAD, 0x01),//0x20010400,
/*Page program*/
[4 * 9 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0x12, CMD_DDR, FLEXSPI_8PAD, 0xED),//0x87ed8712,
[4 * 9 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, WRITE_DDR, FLEXSPI_8PAD, 0x04),//0xa3048b20,
},
},
.pageSize = 256u,
.sectorSize = 4u * 1024u,
.blockSize = 64u * 1024u,
.isUniformBlockSize = false,
.ipcmdSerialClkFreq = 1,
.serialNorType = 2,
.reserve2[0] = 0x7008200,
};
@@ -1,352 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_flexspi_nor_flash.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
#define __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief XIP_BOARD driver version 2.0.0. */
#define FSL_XIP_BOARD_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/* FLEXSPI memory config block related defintions */
#define FLEXSPI_CFG_BLK_TAG (0x42464346UL) // ascii "FCFB" Big Endian
#define FLEXSPI_CFG_BLK_VERSION (0x56010400UL) // V1.4.0
#define FLEXSPI_CFG_BLK_SIZE (512)
/* FLEXSPI Feature related definitions */
#define FLEXSPI_FEATURE_HAS_PARALLEL_MODE 1
/* Lookup table related defintions */
#define CMD_INDEX_READ 0
#define CMD_INDEX_READSTATUS 1
#define CMD_INDEX_WRITEENABLE 2
#define CMD_INDEX_WRITE 4
#define CMD_LUT_SEQ_IDX_READ 0
#define CMD_LUT_SEQ_IDX_READSTATUS 1
#define CMD_LUT_SEQ_IDX_WRITEENABLE 3
#define CMD_LUT_SEQ_IDX_WRITE 9
#define CMD_SDR 0x01
#define CMD_DDR 0x21
#define RADDR_SDR 0x02
#define RADDR_DDR 0x22
#define CADDR_SDR 0x03
#define CADDR_DDR 0x23
#define MODE1_SDR 0x04
#define MODE1_DDR 0x24
#define MODE2_SDR 0x05
#define MODE2_DDR 0x25
#define MODE4_SDR 0x06
#define MODE4_DDR 0x26
#define MODE8_SDR 0x07
#define MODE8_DDR 0x27
#define WRITE_SDR 0x08
#define WRITE_DDR 0x28
#define READ_SDR 0x09
#define READ_DDR 0x29
#define LEARN_SDR 0x0A
#define LEARN_DDR 0x2A
#define DATSZ_SDR 0x0B
#define DATSZ_DDR 0x2B
#define DUMMY_SDR 0x0C
#define DUMMY_DDR 0x2C
#define DUMMY_RWDS_SDR 0x0D
#define DUMMY_RWDS_DDR 0x2D
#define JMP_ON_CS 0x1F
#define STOP_EXE 0
#define FLEXSPI_1PAD 0
#define FLEXSPI_2PAD 1
#define FLEXSPI_4PAD 2
#define FLEXSPI_8PAD 3
/*! @name LUT - LUT 0..LUT 63 */
/*! @{ */
#define FLEXSPI_LUT_OPERAND0_MASK (0xFFU)
#define FLEXSPI_LUT_OPERAND0_SHIFT (0U)
/*! OPERAND0 - OPERAND0
*/
#define FLEXSPI_LUT_OPERAND0(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND0_SHIFT)) & FLEXSPI_LUT_OPERAND0_MASK)
#define FLEXSPI_LUT_NUM_PADS0_MASK (0x300U)
#define FLEXSPI_LUT_NUM_PADS0_SHIFT (8U)
/*! NUM_PADS0 - NUM_PADS0
*/
#define FLEXSPI_LUT_NUM_PADS0(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS0_SHIFT)) & FLEXSPI_LUT_NUM_PADS0_MASK)
#define FLEXSPI_LUT_OPCODE0_MASK (0xFC00U)
#define FLEXSPI_LUT_OPCODE0_SHIFT (10U)
/*! OPCODE0 - OPCODE
*/
#define FLEXSPI_LUT_OPCODE0(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE0_SHIFT)) & FLEXSPI_LUT_OPCODE0_MASK)
#define FLEXSPI_LUT_OPERAND1_MASK (0xFF0000U)
#define FLEXSPI_LUT_OPERAND1_SHIFT (16U)
/*! OPERAND1 - OPERAND1
*/
#define FLEXSPI_LUT_OPERAND1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND1_SHIFT)) & FLEXSPI_LUT_OPERAND1_MASK)
#define FLEXSPI_LUT_NUM_PADS1_MASK (0x3000000U)
#define FLEXSPI_LUT_NUM_PADS1_SHIFT (24U)
/*! NUM_PADS1 - NUM_PADS1
*/
#define FLEXSPI_LUT_NUM_PADS1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS1_SHIFT)) & FLEXSPI_LUT_NUM_PADS1_MASK)
#define FLEXSPI_LUT_OPCODE1_MASK (0xFC000000U)
#define FLEXSPI_LUT_OPCODE1_SHIFT (26U)
/*! OPCODE1 - OPCODE1
*/
#define FLEXSPI_LUT_OPCODE1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE1_SHIFT)) & FLEXSPI_LUT_OPCODE1_MASK)
/*! @} */
/* The count of FLEXSPI_LUT */
#define FLEXSPI_LUT_COUNT (64U)
#define FLEXSPI_LUT_SEQ(cmd0, pad0, op0, cmd1, pad1, op1) \
(FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \
FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1))
//!@brief Definitions for FlexSPI Serial Clock Frequency
typedef enum _FlexSpiSerialClockFreq {
kFlexSpiSerialClk_30MHz = 1,
kFlexSpiSerialClk_50MHz = 2,
kFlexSpiSerialClk_60MHz = 3,
kFlexSpiSerialClk_80MHz = 4,
kFlexSpiSerialClk_100MHz = 5,
kFlexSpiSerialClk_120MHz = 6,
kFlexSpiSerialClk_133MHz = 7,
kFlexSpiSerialClk_166MHz = 8,
kFlexSpiSerialClk_200MHz = 9,
} flexspi_serial_clk_freq_t;
//!@brief FlexSPI clock configuration type
enum {
kFlexSpiClk_SDR, //!< Clock configure for SDR mode
kFlexSpiClk_DDR, //!< Clock configurat for DDR mode
};
//!@brief FlexSPI Read Sample Clock Source definition
typedef enum _FlashReadSampleClkSource {
kFlexSPIReadSampleClk_LoopbackInternally = 0,
kFlexSPIReadSampleClk_LoopbackFromDqsPad = 1,
kFlexSPIReadSampleClk_LoopbackFromSckPad = 2,
kFlexSPIReadSampleClk_ExternalInputFromDqsPad = 3,
} flexspi_read_sample_clk_t;
//!@brief Misc feature bit definitions
enum {
kFlexSpiMiscOffset_DiffClkEnable = 0, //!< Bit for Differential clock enable
kFlexSpiMiscOffset_Ck2Enable = 1, //!< Bit for CK2 enable
kFlexSpiMiscOffset_ParallelEnable = 2, //!< Bit for Parallel mode enable
kFlexSpiMiscOffset_WordAddressableEnable = 3, //!< Bit for Word Addressable enable
kFlexSpiMiscOffset_SafeConfigFreqEnable = 4, //!< Bit for Safe Configuration Frequency enable
kFlexSpiMiscOffset_PadSettingOverrideEnable = 5, //!< Bit for Pad setting override enable
kFlexSpiMiscOffset_DdrModeEnable = 6, //!< Bit for DDR clock confiuration indication.
};
//!@brief Flash Type Definition
enum {
kFlexSpiDeviceType_SerialNOR = 1, //!< Flash devices are Serial NOR
kFlexSpiDeviceType_SerialNAND = 2, //!< Flash devices are Serial NAND
kFlexSpiDeviceType_SerialRAM = 3, //!< Flash devices are Serial RAM/HyperFLASH
kFlexSpiDeviceType_MCP_NOR_NAND = 0x12, //!< Flash device is MCP device, A1 is Serial NOR, A2 is Serial NAND
kFlexSpiDeviceType_MCP_NOR_RAM = 0x13, //!< Flash deivce is MCP device, A1 is Serial NOR, A2 is Serial RAMs
};
//!@brief Flash Pad Definitions
enum {
kSerialFlash_1Pad = 1,
kSerialFlash_2Pads = 2,
kSerialFlash_4Pads = 4,
kSerialFlash_8Pads = 8,
};
//!@brief FlexSPI LUT Sequence structure
typedef struct _lut_sequence {
uint8_t seqNum; //!< Sequence Number, valid number: 1-16
uint8_t seqId; //!< Sequence Index, valid number: 0-15
uint16_t reserved;
} flexspi_lut_seq_t;
//!@brief Flash Configuration Command Type
enum {
kDeviceConfigCmdType_Generic, //!< Generic command, for example: configure dummy cycles, drive strength, etc
kDeviceConfigCmdType_QuadEnable, //!< Quad Enable command
kDeviceConfigCmdType_Spi2Xpi, //!< Switch from SPI to DPI/QPI/OPI mode
kDeviceConfigCmdType_Xpi2Spi, //!< Switch from DPI/QPI/OPI to SPI mode
kDeviceConfigCmdType_Spi2NoCmd, //!< Switch to 0-4-4/0-8-8 mode
kDeviceConfigCmdType_Reset, //!< Reset device command
};
typedef struct {
uint8_t time_100ps; /* Data valid time, in terms of 100ps */
uint8_t delay_cells; /* Data valid time, in terms of delay cells */
} flexspi_dll_time_t;
/*!
* @name Configuration Option
* @{
*/
/*! @brief Serial NOR Configuration Option. */
typedef struct _serial_nor_config_option {
union {
struct {
uint32_t max_freq : 4; /*!< Maximum supported Frequency */
uint32_t misc_mode : 4; /*!< miscellaneous mode */
uint32_t quad_mode_setting : 4; /*!< Quad mode setting */
uint32_t cmd_pads : 4; /*!< Command pads */
uint32_t query_pads : 4; /*!< SFDP read pads */
uint32_t device_type : 4; /*!< Device type */
uint32_t option_size : 4; /*!< Option size, in terms of uint32_t, size = (option_size + 1) * 4 */
uint32_t tag : 4; /*!< Tag, must be 0x0E */
} B;
uint32_t U;
} option0;
union {
struct {
uint32_t dummy_cycles : 8; /*!< Dummy cycles before read */
uint32_t status_override : 8; /*!< Override status register value during device mode configuration */
uint32_t pinmux_group : 4; /*!< The pinmux group selection */
uint32_t dqs_pinmux_group : 4; /*!< The DQS Pinmux Group Selection */
uint32_t drive_strength : 4; /*!< The Drive Strength of FlexSPI Pads */
uint32_t flash_connection : 4; /*!< Flash connection option: 0 - Single Flash connected to port A, 1 -
Parallel mode, 2 - Single Flash connected to Port B */
} B;
uint32_t U;
} option1;
} serial_nor_config_option_t;
//!@brief FlexSPI Memory Configuration Block
struct mem_config_s {
uint32_t tag; //!< [0x000-0x003] Tag, fixed value 0x42464346UL
uint32_t version; //!< [0x004-0x007] Version,[31:24] -'V', [23:16] - Major, [15:8] - Minor, [7:0] - bugfix
uint32_t reserved0; //!< [0x008-0x00b] Reserved for future use
uint8_t readSampleClkSrc; //!< [0x00c-0x00c] Read Sample Clock Source, valid value: 0/1/3
uint8_t csHoldTime; //!< [0x00d-0x00d] CS hold time, default value: 3
uint8_t csSetupTime; //!< [0x00e-0x00e] CS setup time, default value: 3
uint8_t columnAddressWidth; //!< [0x00f-0x00f] Column Address with, for HyperBus protocol, it is fixed to 3, For Serial NAND, need to refer to datasheet
uint8_t deviceModeCfgEnable; //!< [0x010-0x010] Device Mode Configure enable flag, 1 - Enable, 0 - Disable
uint8_t deviceModeType; //!< [0x011-0x011] Specify the configuration command type:Quad Enable, DPI/QPI/OPI switch, Generic configuration, etc.
uint16_t waitTimeCfgCommands; //!< [0x012-0x013] Wait time for all configuration commands, unit: 100us, Used for DPI/QPI/OPI switch or reset command
flexspi_lut_seq_t
deviceModeSeq; //!< [0x014-0x017] Device mode sequence info, [7:0] - LUT sequence id, [15:8] - LUt sequence number, [31:16] Reserved
uint32_t deviceModeArg; //!< [0x018-0x01b] Argument/Parameter for device configuration
uint8_t configCmdEnable; //!< [0x01c-0x01c] Configure command Enable Flag, 1 - Enable, 0 - Disable
uint8_t configModeType[3]; //!< [0x01d-0x01f] Configure Mode Type, similar as deviceModeTpe
flexspi_lut_seq_t
configCmdSeqs[3]; //!< [0x020-0x02b] Sequence info for Device Configuration command, similar as deviceModeSeq
uint32_t reserved1; //!< [0x02c-0x02f] Reserved for future use
uint32_t configCmdArgs[3]; //!< [0x030-0x03b] Arguments/Parameters for device Configuration commands
uint32_t reserved2; //!< [0x03c-0x03f] Reserved for future use
uint32_t controllerMiscOption; //!< [0x040-0x043] Controller Misc Options, see Misc feature bit definitions for more details
uint8_t deviceType; //!< [0x044-0x044] Device Type: See Flash Type Definition for more details
uint8_t sflashPadType; //!< [0x045-0x045] Serial Flash Pad Type: 1 - Single, 2 - Dual, 4 - Quad, 8 - Octal
uint8_t serialClkFreq; //!< [0x046-0x046] Serial Flash Frequencey, device specific definitions, See System Boot Chapter for more details
uint8_t lutCustomSeqEnable; //!< [0x047-0x047] LUT customization Enable, it is required if the program/erase cannot be done using 1 LUT sequence, currently, only applicable to HyperFLASH
uint32_t reserved3[2]; //!< [0x048-0x04f] Reserved for future use
uint32_t sflashA1Size; //!< [0x050-0x053] Size of Flash connected to A1
uint32_t sflashA2Size; //!< [0x054-0x057] Size of Flash connected to A2
uint32_t sflashB1Size; //!< [0x058-0x05b] Size of Flash connected to B1
uint32_t sflashB2Size; //!< [0x05c-0x05f] Size of Flash connected to B2
uint32_t csPadSettingOverride; //!< [0x060-0x063] CS pad setting override value
uint32_t sclkPadSettingOverride; //!< [0x064-0x067] SCK pad setting override value
uint32_t dataPadSettingOverride; //!< [0x068-0x06b] data pad setting override value
uint32_t dqsPadSettingOverride; //!< [0x06c-0x06f] DQS pad setting override value
uint32_t timeoutInMs; //!< [0x070-0x073] Timeout threshold for read status command
uint32_t commandInterval; //!< [0x074-0x077] CS deselect interval between two commands
flexspi_dll_time_t
dataValidTime[2]; //!< [0x078-0x07b] CLK edge to data valid time for PORT A and PORT B, in terms of 0.1ns
uint16_t busyOffset; //!< [0x07c-0x07d] Busy offset, valid value: 0-31
uint16_t busyBitPolarity; //!< [0x07e-0x07f] Busy flag polarity, 0 - busy flag is 1 when flash device is busy, 1 busy flag is 0 when flash device is busy
uint32_t lookupTable[64]; //!< [0x080-0x17f] Lookup table holds Flash command sequences
flexspi_lut_seq_t lutCustomSeq[12]; //!< [0x180-0x1af] Customizable LUT Sequences
uint32_t reserved4[4]; //!< [0x1b0-0x1bf] Reserved for future use
};
/* */
#define NOR_CMD_INDEX_READ CMD_INDEX_READ //!< 0
#define NOR_CMD_INDEX_READSTATUS CMD_INDEX_READSTATUS //!< 1
#define NOR_CMD_INDEX_WRITEENABLE CMD_INDEX_WRITEENABLE //!< 2
#define NOR_CMD_INDEX_ERASESECTOR 3 //!< 3
#define NOR_CMD_INDEX_PAGEPROGRAM CMD_INDEX_WRITE //!< 4
#define NOR_CMD_INDEX_CHIPERASE 5 //!< 5
#define NOR_CMD_INDEX_DUMMY 6 //!< 6
#define NOR_CMD_INDEX_ERASEBLOCK 7 //!< 7
#define NOR_CMD_LUT_SEQ_IDX_READ CMD_LUT_SEQ_IDX_READ //!< 0 READ LUT sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS \
CMD_LUT_SEQ_IDX_READSTATUS //!< 1 Read Status LUT sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS_XPI \
2 //!< 2 Read status DPI/QPI/OPI sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE \
CMD_LUT_SEQ_IDX_WRITEENABLE //!< 3 Write Enable sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE_XPI \
4 //!< 4 Write Enable DPI/QPI/OPI sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_ERASESECTOR 5 //!< 5 Erase Sector sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_ERASEBLOCK 8 //!< 8 Erase Block sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_PAGEPROGRAM \
CMD_LUT_SEQ_IDX_WRITE //!< 9 Program sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_CHIPERASE 11 //!< 11 Chip Erase sequence in lookupTable id stored in config block
#define NOR_CMD_LUT_SEQ_IDX_READ_SFDP 13 //!< 13 Read SFDP sequence in lookupTable id stored in config block
#define NOR_CMD_LUT_SEQ_IDX_RESTORE_NOCMD \
14 //!< 14 Restore 0-4-4/0-8-8 mode sequence id in lookupTable stored in config block
#define NOR_CMD_LUT_SEQ_IDX_EXIT_NOCMD \
15 //!< 15 Exit 0-4-4/0-8-8 mode sequence id in lookupTable stored in config blobk
/*
* Serial NOR configuration block
*/
struct flexspi_nor_config_s {
struct mem_config_s memConfig; //!< Common memory configuration info via FlexSPI
uint32_t pageSize; //!< Page size of Serial NOR
uint32_t sectorSize; //!< Sector size of Serial NOR
uint8_t ipcmdSerialClkFreq; //!< Clock frequency for IP command
uint8_t isUniformBlockSize; //!< Sector/Block size is the same
uint8_t reserved0[2]; //!< Reserved for future use
uint8_t serialNorType; //!< Serial NOR Flash type: 0/1/2/3
uint8_t needExitNoCmdMode; //!< Need to exit NoCmd mode before other IP command
uint8_t halfClkForNonReadCmd; //!< Half the Serial Clock for non-read command: true/false
uint8_t needRestoreNoCmdMode; //!< Need to Restore NoCmd mode after IP commmand execution
uint32_t blockSize; //!< Block size
uint32_t reserve2[11]; //!< Reserved for future use
};
extern const struct flexspi_nor_config_s g_flash_config;
extern const struct flexspi_nor_config_s g_flash_fast_config;
#endif /* __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */
-271
View File
@@ -1,271 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_romapi.c
*
* Copyright 2017-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*
****************************************************************************/
/****************************************************************************
*
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <debug.h>
#include <stdint.h>
#include <stdbool.h>
#include "arm_internal.h"
#include "imxrt_flexspi_nor_flash.h"
#include "imxrt_romapi.h"
#include <hardware/rt117x/imxrt117x_anadig.h>
/*******************************************************************************
* Definitions
******************************************************************************/
/*!
* @brief Structure of version property.
*
* @ingroup bl_core
*/
typedef union _standard_version {
struct {
uint8_t bugfix; /*!< bugfix version [7:0] */
uint8_t minor; /*!< minor version [15:8] */
uint8_t major; /*!< major version [23:16] */
char name; /*!< name [31:24] */
};
uint32_t version; /*!< combined version numbers */
#if defined(__cplusplus)
StandardVersion() : version(0) {
}
StandardVersion(uint32_t version) : version(version) {
}
#endif
} standard_version_t;
/*!
* @brief Interface for the ROM FLEXSPI NOR flash driver.
*/
typedef struct {
uint32_t version;
status_t (*init)(uint32_t instance, flexspi_nor_config_t *config);
status_t (*page_program)(uint32_t instance, flexspi_nor_config_t *config, uint32_t dst_addr, const uint32_t *src);
status_t (*erase_all)(uint32_t instance, flexspi_nor_config_t *config);
status_t (*erase)(uint32_t instance, flexspi_nor_config_t *config, uint32_t start, uint32_t length);
status_t (*read)(uint32_t instance, flexspi_nor_config_t *config, uint32_t *dst, uint32_t start, uint32_t bytes);
void (*clear_cache)(uint32_t instance);
status_t (*xfer)(uint32_t instance, flexspi_xfer_t *xfer);
status_t (*update_lut)(uint32_t instance, uint32_t seqIndex, const uint32_t *lutBase, uint32_t numberOfSeq);
status_t (*get_config)(uint32_t instance, flexspi_nor_config_t *config, serial_nor_config_option_t *option);
status_t (*erase_sector)(uint32_t instance, flexspi_nor_config_t *config, uint32_t address);
status_t (*erase_block)(uint32_t instance, flexspi_nor_config_t *config, uint32_t address);
const uint32_t reserved0; /*!< Reserved */
status_t (*wait_busy)(uint32_t instance, flexspi_nor_config_t *config, bool isParallelMode, uint32_t address);
const uint32_t reserved1[2]; /*!< Reserved */
} flexspi_nor_driver_interface_t;
/*!
* @brief Root of the bootloader api tree.
*
* An instance of this struct resides in read-only memory in the bootloader. It
* provides a user application access to APIs exported by the bootloader.
*
* @note The order of existing fields must not be changed.
*/
typedef struct {
void (*runBootloader)(void *arg); /*!< Function to start the bootloader executing.*/
standard_version_t version; /*!< Bootloader version number.*/
const char *copyright; /*!< Copyright string.*/
const flexspi_nor_driver_interface_t *flexSpiNorDriver; /*!< FlexSPI NOR FLASH Driver API.*/
const uint32_t reserved[8]; /*!< Reserved */
} bootloader_api_entry_t;
/*******************************************************************************
* Variables
******************************************************************************/
static bootloader_api_entry_t *g_bootloaderTree = NULL;
/*******************************************************************************
* ROM FLEXSPI NOR driver
******************************************************************************/
/*!
* @brief ROM API init.
*/
locate_code(".ramfunc")
void ROM_API_Init(void)
{
if ((getreg32(IMXRT_ANADIG_MISC_MISC_DIFPROG) & ANADIG_MISC_MISC_DIFPROG_CHIPID(0x10U)) != 0U) {
g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0021001cU);
} else {
g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0020001cU);
}
}
/*!
* @brief Enter Bootloader.
*
* @param arg A pointer to the storage for the bootloader param.
* refer to System Boot Chapter in device reference manual for details.
*/
locate_code(".ramfunc")
void ROM_RunBootloader(void *arg)
{
g_bootloaderTree->runBootloader(arg);
}
/*! @brief Get FLEXSPI NOR Configuration Block based on specified option. */
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_GetConfig(uint32_t instance,
flexspi_nor_config_t *config,
serial_nor_config_option_t *option)
{
return g_bootloaderTree->flexSpiNorDriver->get_config(instance, config, option);
}
/*!
* @brief Initialize Serial NOR devices via FLEXSPI.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_Init(uint32_t instance, flexspi_nor_config_t *config)
{
return g_bootloaderTree->flexSpiNorDriver->init(instance, config);
}
/*!
* @brief Program data to Serial NOR via FLEXSPI.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param dst_addr A pointer to the desired flash memory to be programmed.
* @param src A pointer to the source buffer of data that is to be programmed
* into the NOR flash.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_ProgramPage(uint32_t instance,
flexspi_nor_config_t *config,
uint32_t dst_addr,
const uint32_t *src)
{
return g_bootloaderTree->flexSpiNorDriver->page_program(instance, config, dst_addr, src);
}
/*!
* @brief Read data from Serial NOR
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param dst A pointer to the dest buffer of data that is to be read from the NOR flash.
* @param lengthInBytes The length, given in bytes to be read.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_Read(
uint32_t instance, flexspi_nor_config_t *config, uint32_t *dst, uint32_t start, uint32_t lengthInBytes)
{
return g_bootloaderTree->flexSpiNorDriver->read(instance, config, dst, start, lengthInBytes);
}
/*!
* @brief Erase Flash Region specified by address and length.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
* @param length The length, given in bytes to be erased.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *config, uint32_t start, uint32_t length)
{
return g_bootloaderTree->flexSpiNorDriver->erase(instance, config, start, length);
}
/*!
* @brief Erase one sector specified by address.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_t *config, uint32_t start)
{
return g_bootloaderTree->flexSpiNorDriver->erase_sector(instance, config, start);
}
/*!
* @brief Erase one block specified by address.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t *config, uint32_t start)
{
return g_bootloaderTree->flexSpiNorDriver->erase_block(instance, config, start);
}
/*! @brief Erase all the Serial NOR devices connected on FLEXSPI. */
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_EraseAll(uint32_t instance, flexspi_nor_config_t *config)
{
return g_bootloaderTree->flexSpiNorDriver->erase_all(instance, config);
}
/*! @brief FLEXSPI command */
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_CommandXfer(uint32_t instance, flexspi_xfer_t *xfer)
{
return g_bootloaderTree->flexSpiNorDriver->xfer(instance, xfer);
}
/*! @brief Configure FLEXSPI Lookup table. */
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance,
uint32_t seqIndex,
const uint32_t *lutBase,
uint32_t seqNumber)
{
return g_bootloaderTree->flexSpiNorDriver->update_lut(instance, seqIndex, lutBase, seqNumber);
}
/*! @brief Software reset for the FLEXSPI logic. */
locate_code(".ramfunc")
void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance)
{
uint32_t clearCacheFunctionAddress;
if ((getreg32(IMXRT_ANADIG_MISC_MISC_DIFPROG) & ANADIG_MISC_MISC_DIFPROG_CHIPID(0x10U)) != 0U) {
clearCacheFunctionAddress = 0x0021a3b7U;
} else {
clearCacheFunctionAddress = 0x0020426bU;
}
clearCacheCommand_t clearCacheCommand;
MISRA_CAST(clearCacheCommand_t, clearCacheCommand, uint32_t, clearCacheFunctionAddress);
(void)clearCacheCommand(instance);
}
/*! @brief Wait until device is idle*/
locate_code(".ramfunc")
status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance,
flexspi_nor_config_t *config,
bool isParallelMode,
uint32_t address)
{
return g_bootloaderTree->flexSpiNorDriver->wait_busy(instance, config, isParallelMode, address);
}
-373
View File
@@ -1,373 +0,0 @@
/****************************************************************************
* boards/px4/fmu-v6xrt/src/imxrt_romapi.c
*
* Copyright 2017-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*
****************************************************************************/
#ifndef __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_ROMAPI_H
#define __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_ROMAPI_H
/****************************************************************************
*
* Included Files
****************************************************************************/
#include "board_config.h"
typedef int32_t status_t;
typedef struct flexspi_nor_config_s flexspi_nor_config_t;
typedef status_t (*clearCacheCommand_t)(uint32_t instance);
/*! @brief FLEXSPI Operation Context */
typedef enum _flexspi_operation {
kFLEXSPIOperation_Command, /*!< FLEXSPI operation: Only command, both TX and RX buffer are ignored. */
kFLEXSPIOperation_Config, /*!< FLEXSPI operation: Configure device mode, the TX FIFO size is fixed in LUT. */
kFLEXSPIOperation_Write, /*!< FLEXSPI operation: Write, only TX buffer is effective */
kFLEXSPIOperation_Read, /*!< FLEXSPI operation: Read, only Rx Buffer is effective. */
} flexspi_operation_t;
#define kFLEXSPIOperation_End kFLEXSPIOperation_Read
/*! @brief FLEXSPI Transfer Context */
typedef struct _flexspi_xfer {
flexspi_operation_t operation; /*!< FLEXSPI operation */
uint32_t baseAddress; /*!< FLEXSPI operation base address */
uint32_t seqId; /*!< Sequence Id */
uint32_t seqNum; /*!< Sequence Number */
bool isParallelModeEnable; /*!< Is a parallel transfer */
uint32_t *txBuffer; /*!< Tx buffer */
uint32_t txSize; /*!< Tx size in bytes */
uint32_t *rxBuffer; /*!< Rx buffer */
uint32_t rxSize; /*!< Rx size in bytes */
} flexspi_xfer_t;
/*! @brief convert the type for MISRA */
#define MISRA_CAST(to_type, to_var, from_type, from_var) \
do \
{ \
union \
{ \
to_type to_var_tmp; \
from_type from_var_tmp; \
} type_converter_var = {.from_var_tmp = (from_var)}; \
(to_var) = type_converter_var.to_var_tmp; \
} while (false)
#ifdef __cplusplus
extern "C" {
#endif
extern struct flexspi_nor_config_s g_bootConfig;
/*!
* @brief ROM API init
*
* Get the bootloader api entry address.
*/
void ROM_API_Init(void);
/*!
* @name Enter Bootloader
* @{
*/
/*!
* @brief Enter Bootloader.
*
* @param arg A pointer to the storage for the bootloader param.
* refer to System Boot Chapter in device reference manual for details.
*/
void ROM_RunBootloader(void *arg);
/*@}*/
/*!
* @name GetConfig
* @{
*/
/*!
* @brief Get FLEXSPI NOR Configuration Block based on specified option.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param option A pointer to the storage Serial NOR Configuration Option Context.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_GetConfig(uint32_t instance,
flexspi_nor_config_t *config,
serial_nor_config_option_t *option);
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initialize Serial NOR devices via FLEXSPI
*
* This function checks and initializes the FLEXSPI module for the other FLEXSPI APIs.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_Init(uint32_t instance, flexspi_nor_config_t *config);
/*@}*/
/*!
* @name Programming
* @{
*/
/*!
* @brief Program data to Serial NOR via FLEXSPI.
*
* This function programs the NOR flash memory with the dest address for a given
* flash area as determined by the dst address and the length.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param dst_addr A pointer to the desired flash memory to be programmed.
* @note It is recommended that use page aligned access;
* If the dst_addr is not aligned to page, the driver automatically
* aligns address down with the page address.
* @param src A pointer to the source buffer of data that is to be programmed
* into the NOR flash.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_ProgramPage(uint32_t instance,
flexspi_nor_config_t *config,
uint32_t dst_addr,
const uint32_t *src);
/*@}*/
/*!
* @name Reading
* @{
*/
/*!
* @brief Read data from Serial NOR via FLEXSPI.
*
* This function read the NOR flash memory with the start address for a given
* flash area as determined by the dst address and the length.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param dst A pointer to the dest buffer of data that is to be read from the NOR flash.
* @note It is recommended that use page aligned access;
* If the dstAddr is not aligned to page, the driver automatically
* aligns address down with the page address.
* @param start The start address of the desired NOR flash memory to be read.
* @param lengthInBytes The length, given in bytes to be read.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_Read(
uint32_t instance, flexspi_nor_config_t *config, uint32_t *dst, uint32_t start, uint32_t lengthInBytes);
/*@}*/
/*!
* @name Erasing
* @{
*/
/*!
* @brief Erase Flash Region specified by address and length
*
* This function erases the appropriate number of flash sectors based on the
* desired start address and length.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
* @note It is recommended that use sector-aligned access nor device;
* If dstAddr is not aligned with the sector,the driver automatically
* aligns address down with the sector address.
* @param length The length, given in bytes to be erased.
* @note It is recommended that use sector-aligned access nor device;
* If length is not aligned with the sector,the driver automatically
* aligns up with the sector.
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *config, uint32_t start, uint32_t length);
/*!
* @brief Erase one sector specified by address
*
* This function erases one of NOR flash sectors based on the desired address.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
* @note It is recommended that use sector-aligned access nor device;
* If dstAddr is not aligned with the sector, the driver automatically
* aligns address down with the sector address.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_t *config, uint32_t start);
/*!
* @brief Erase one block specified by address
*
* This function erases one block of NOR flash based on the desired address.
*
* @param instance storage the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
* @param start The start address of the desired NOR flash memory to be erased.
* @note It is recommended that use block-aligned access nor device;
* If dstAddr is not aligned with the block, the driver automatically
* aligns address down with the block address.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t *config, uint32_t start);
/*!
* @brief Erase all the Serial NOR devices connected on FLEXSPI.
*
* @param instance storage the instance of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
*/
status_t ROM_FLEXSPI_NorFlash_EraseAll(uint32_t instance, flexspi_nor_config_t *config);
/*@}*/
/*!
* @name Command
* @{
*/
/*!
* @brief FLEXSPI command
*
* This function is used to perform the command write sequence to the NOR device.
*
* @param instance storage the index of FLEXSPI.
* @param xfer A pointer to the storage FLEXSPI Transfer Context.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
*/
status_t ROM_FLEXSPI_NorFlash_CommandXfer(uint32_t instance, flexspi_xfer_t *xfer);
/*@}*/
/*!
* @name UpdateLut
* @{
*/
/*!
* @brief Configure FLEXSPI Lookup table
*
* @param instance storage the index of FLEXSPI.
* @param seqIndex storage the sequence Id.
* @param lutBase A pointer to the look-up-table for command sequences.
* @param seqNumber storage sequence number.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
*/
status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance,
uint32_t seqIndex,
const uint32_t *lutBase,
uint32_t seqNumber);
/*@}*/
/*!
* @name Device status
* @{
*/
/*!
* @brief Wait until device is idle.
*
* @param instance Indicates the index of FLEXSPI.
* @param config A pointer to the storage for the driver runtime state
* @param isParallelMode Indicates whether NOR flash is in parallel mode.
* @param address Indicates the operation(erase/program/read) address for serial NOR flash.
*
* @retval kStatus_Success Api was executed successfully.
* @retval kStatus_InvalidArgument A invalid argument is provided.
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout Device timeout.
*/
status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance,
flexspi_nor_config_t *config,
bool isParallelMode,
uint32_t address);
/*@}*/
/*!
* @name ClearCache
* @{
*/
/*!
* @name ClearCache
* @{
*/
/*!
* @brief Software reset for the FLEXSPI logic.
*
* This function sets the software reset flags for both AHB and buffer domain and
* resets both AHB buffer and also IP FIFOs.
*
* @param instance storage the index of FLEXSPI.
*/
void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance);
/*@}*/
#endif /* __BOARDS_PX4_FMU_V6XRT_SRC_IMXRT_ROMAPI_H */
-133
View File
@@ -1,133 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
static const px4_mft_device_t qspi_flash = { // FM25V02A on FMUM 32K 512 X 64
.bus_type = px4_mft_device_t::FLEXSPI, // Using Flex SPI
};
// KiB BS nB
static const px4_mft_device_t i2c3 = { // 24LC64T on IMU 8K 32 X 256
.bus_type = px4_mft_device_t::I2C,
.devid = PX4_MK_I2C_DEVID(3, 0x50)
};
static const px4_mft_device_t i2c6 = { // 24LC64T on BASE 8K 32 X 256
.bus_type = px4_mft_device_t::I2C,
.devid = PX4_MK_I2C_DEVID(6, 0x51)
};
static const px4_mtd_entry_t fmum_fram = {
.device = &qspi_flash,
.npart = 2,
.partd = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 32
},
{
.type = MTD_WAYPOINTS,
.path = "/fs/mtd_waypoints",
.nblocks = 32
}
},
};
static const px4_mtd_entry_t base_eeprom = {
.device = &i2c6,
.npart = 2,
.partd = {
{
.type = MTD_MFT_VER,
.path = "/fs/mtd_mft_ver",
.nblocks = 248
},
{
.type = MTD_NET,
.path = "/fs/mtd_net",
.nblocks = 8 // 256 = 32 * 8
}
},
};
static const px4_mtd_entry_t imu_eeprom = {
.device = &i2c3,
.npart = 3,
.partd = {
{
.type = MTD_CALDATA,
.path = "/fs/mtd_caldata",
.nblocks = 240
},
{
.type = MTD_MFT_REV,
.path = "/fs/mtd_mft_rev",
.nblocks = 8
},
{
.type = MTD_ID,
.path = "/fs/mtd_id",
.nblocks = 8 // 256 = 32 * 8
}
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 3,
.entries = {
&fmum_fram,
&base_eeprom,
&imu_eeprom
}
};
static const px4_mft_entry_s mtd_mft = {
.type = MTD,
.pmft = (void *) &board_mtd_config,
};
static const px4_mft_s mft = {
.nmft = 1,
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
{
return &mft;
}
-87
View File
@@ -1,87 +0,0 @@
/************************************************************************************
*
* Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_config.h>
#include <px4_log.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <systemlib/px4_macros.h>
#include <px4_platform/gpio.h>
#include <arm_internal.h>
#include <chip.h>
#include "imxrt_lpspi.h"
#include "imxrt_gpio.h"
#include "board_config.h"
#include <systemlib/err.h>
#ifdef CONFIG_IMXRT_LPSPI
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port2, GPIO::Pin11}, SPI::DRDY{GPIO::Port3, GPIO::Pin19}), /* GPIO_EMC_B2_01 GPIO2_IO11, GPIO_AD_20, GPIO3_IO19 */
}, {GPIO::Port2, GPIO::Pin1}), // Power GPIO_EMC_B1_33 GPIO2_IO01
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port3, GPIO::Pin24}, SPI::DRDY{GPIO::Port2, GPIO::Pin7}), /* GPIO_AD_25 GPIO3_IO24, GPIO_EMC_B1_39 GPIO2_IO07 */
}, {GPIO::Port1, GPIO::Pin22}), // Power GPIO_EMC_B1_22 GPIO1_IO22
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin28}), /* GPIO_EMC_B2_08 GPIO2_IO18, GPIO_EMC_B2_18 GPIO2_IO28 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin15}), /* GPIO_EMC_B2_05 GPIO2_IO15 */
}, {GPIO::Port1, GPIO::Pin14}), // Power GPIO_EMC_B1_14 GPIO1_IO14
initSPIBusExternal(SPI::Bus::LPSPI6, {
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin9}, SPI::DRDY{GPIO::Port1, GPIO::Pin5}), /* GPIO_LPSR_09 GPIO6_IO09 GPIO_EMC_B1_05 GPIO1_IO05*/
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
}),
};
#endif
static constexpr bool unused = validateSPIConfig(px4_spi_buses);

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