mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-21 20:04:09 +08:00
[chibios] Add STM32H7 (#2859)
* [chibios] Add STM32H7 * [chibios] Update to latest version * [chibios] Cleanup board configuration * [chibios] Cleanup peripheral drivers * [chibios] Fix bootloader interrupt vector done inside ChibiOS * [sdlogger] Enable RTC by default * [chibios] Fix DMA buffers SPI/I2C * [formatting] Fix formatting/styling of files * [chibios] Change PWM configuration (small fixes i2c and makefile) * [chibios] Generic board files * [boards] Fix apogee board * [conf] Cleanup airframes and remove Navstik board
This commit is contained in:
+2
-2
@@ -6,10 +6,10 @@
|
||||
url = https://github.com/paparazzi/luftboot.git
|
||||
[submodule "sw/ext/fatfs"]
|
||||
path = sw/ext/fatfs
|
||||
url = https://github.com/enacuavlab/fatfs.git
|
||||
url = https://github.com/paparazzi/fatfs.git
|
||||
[submodule "sw/ext/chibios"]
|
||||
path = sw/ext/chibios
|
||||
url = https://github.com/ChibiOS/ChibiOS.git
|
||||
url = https://github.com/paparazzi/ChibiOS.git
|
||||
[submodule "sw/ext/libzbar"]
|
||||
path = sw/ext/libzbar
|
||||
url = https://github.com/paparazzi/libzbar
|
||||
|
||||
Vendored
+2
-4
@@ -9,9 +9,7 @@
|
||||
"editor.tabSize": 4,
|
||||
},
|
||||
"files.associations": {
|
||||
"mateksys_3901_l0x.h": "c",
|
||||
"stdlib.h": "c",
|
||||
"iterator": "cpp",
|
||||
"tensor": "cpp"
|
||||
"Makefile.*": "makefile"
|
||||
},
|
||||
"C_Cpp.dimInactiveRegions": false,
|
||||
}
|
||||
@@ -26,7 +26,9 @@
|
||||
CHIBIOS = $(PAPARAZZI_SRC)/sw/ext/chibios
|
||||
|
||||
# directory with board defines for chibios platforms (board specific)
|
||||
BOARD_COMMON ?=
|
||||
BOARD_DIR ?= $(BOARD)/chibios
|
||||
CHIBIOS_BOARD_COMMON_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD_COMMON)
|
||||
CHIBIOS_BOARD_DIR = $(PAPARAZZI_SRC)/sw/airborne/boards/$(BOARD_DIR)
|
||||
|
||||
# chibos linker scripts directory
|
||||
@@ -206,11 +208,10 @@ include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/$(CHIBIOS_BOARD_STA
|
||||
# HAL-OSAL files (optional).
|
||||
include $(CHIBIOS)/os/hal/hal.mk
|
||||
include $(CHIBIOS)/os/hal/ports/STM32/$(CHIBIOS_BOARD_PLATFORM)
|
||||
include $(CHIBIOS_BOARD_DIR)/board.mk
|
||||
include $(CHIBIOS)/os/hal/osal/rt-nil/osal.mk
|
||||
# RTOS files (optional).
|
||||
include $(CHIBIOS)/os/rt/rt.mk
|
||||
include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk
|
||||
include $(CHIBIOS)/os/common/ports/ARMv7-M/compilers/GCC/mk/port.mk
|
||||
# Other files (optional).
|
||||
#
|
||||
ifeq ($(USE_FATFS), TRUE)
|
||||
@@ -224,7 +225,7 @@ LDSCRIPT= $(CHIBIOS_LINKER_DIR)/$(CHIBIOS_BOARD_LINKER)
|
||||
# setting.
|
||||
CSRC = $(ALLCSRC) \
|
||||
$(CHIBIOS)/os/various/syscalls.c \
|
||||
$(CHIBIOS_BOARD_MAIN)
|
||||
$(PAPARAZZI_SRC)/sw/airborne/arch/chibios/board.c
|
||||
|
||||
ECSRC = $(filter %.c, $($(TARGET).srcs))
|
||||
ECPPSRC = $(filter %.cpp, $($(TARGET).srcs))
|
||||
@@ -256,7 +257,7 @@ TCPPSRC =
|
||||
# List ASM source files here
|
||||
ASMXSRC = $(STARTUPASM) $(PORTASM) $(OSALASM)
|
||||
|
||||
INCDIR = $(CONFDIR) $(ALLINC) $(CHIBIOS_BOARD_DIR)
|
||||
INCDIR = $(CONFDIR) $(ALLINC) $(CHIBIOS_BOARD_DIR) $(CHIBIOS_BOARD_COMMON_DIR)
|
||||
|
||||
# Output directory and files
|
||||
BUILDDIR := $(AIRCRAFT_BUILD_DIR)/$(TARGET)
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_safety.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ins_extended.xml modules/ahrs_float_invariant.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_invariant.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +29,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_safety.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="yellow"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -62,7 +62,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/guidance_indi.xml modules/stabilization_indi.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/air_data.xml modules/imu_common.xml modules/airspeed_ms45xx_i2c.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/gps.xml modules/guidance_indi.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi.xml"
|
||||
gui_color="#ffff7f7f0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +73,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml [settings/nps.xml]"
|
||||
settings_modules="[modules/gps_ubx_ucenter.xml] modules/gps.xml modules/nav_basic_fw.xml modules/guidance_full_pid_fw.xml modules/stabilization_adaptive_fw.xml modules/airspeed_adc.xml modules/imu_common.xml modules/ahrs_float_dcm.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml [modules/gps_ubx_ucenter.xml] modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
|
||||
gui_color="#ffff7d7d0000"
|
||||
/>
|
||||
<aircraft
|
||||
|
||||
@@ -0,0 +1,365 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- This is a Nedderdrone
|
||||
* Airframe: TUD00328
|
||||
* Autopilot: Pixhawk 4
|
||||
* FBW: Pixhawk 4
|
||||
* Actuators: 12x T-Motor ESC + Motors and 8x Servos (all CAN)
|
||||
* Datalink: Doodlelabs 2.4GHz
|
||||
* GPS: UBlox F9P
|
||||
* RC: SBUS Crossfire
|
||||
-->
|
||||
|
||||
<airframe name="Neddrone5">
|
||||
<description>Neddrone5</description>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="cube_orange">
|
||||
<configure name="PERIODIC_FREQUENCY" value="500"/>
|
||||
<configure name="FLASH_MODE" value="SWD"/>
|
||||
<!--configure name="RTOS_DEBUG" value="1"/-->
|
||||
|
||||
<module name="radio_control" type="sbus">
|
||||
<configure name="SBUS_PORT" value="UART3"/>
|
||||
</module>
|
||||
|
||||
<module name="airspeed" type="ms45xx_i2c">
|
||||
<define name="USE_I2C4"/>
|
||||
<define name="MS45XX_I2C_DEV" value="i2c4"/>
|
||||
</module>
|
||||
|
||||
<module name="scheduling_indi_simple"/>
|
||||
|
||||
<module name="sys_mon"/>
|
||||
|
||||
<!-- Forward FuelCell data back to the GCS -->
|
||||
<!--module name="generic_uart_sensor"/-->
|
||||
|
||||
<!-- Logger -->
|
||||
<module name="flight_recorder"/>
|
||||
|
||||
<!--define name="ADC_CURRENT_DISABLE" value="TRUE"/-->
|
||||
<module name="adc_generic">
|
||||
<configure name="ADC_CHANNEL_GENERIC1" value="ADC_4"/>
|
||||
<configure name="ADC_CHANNEL_GENERIC2" value="ADC_5"/>
|
||||
</module>
|
||||
|
||||
<define name="RADIO_TH_HOLD" value="RADIO_AUX1"/> <!-- Throttle hold in command laws -->
|
||||
<define name="RADIO_FMODE" value="RADIO_AUX2"/> <!-- Throttle curve select -->
|
||||
<define name="RADIO_FBW_MODE" value="RADIO_AUX3"/> <!-- Switch between AP and FBW control -->
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_AUX1"/>
|
||||
|
||||
<!-- Use the external mag (not in NPS target as then it needs to listen to all) -->
|
||||
<define name="INS_EKF2_MAG_ID" value="MAG_LIS3MDL_SENDER_ID"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="radio_control" type="datalink"/>
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
|
||||
<module name="scheduling_indi_simple"/>
|
||||
|
||||
<module name="logger_file">
|
||||
<define name="FILE_LOGGER_PATH" value="/home/ewoud/Documents"/>
|
||||
</module>
|
||||
|
||||
<!--Not dealing with these in the simulation-->
|
||||
<define name="RADIO_TH_HOLD" value="0"/> <!-- Throttle hold in command laws -->
|
||||
<define name="RADIO_FMODE" value="0"/> <!-- Throttle curve select -->
|
||||
<define name="RADIO_FBW_MODE" value="0"/> <!-- Switch between AP and FBW control -->
|
||||
<define name="RADIO_KILL_SWITCH" value="0"/>
|
||||
</target>
|
||||
|
||||
<module name="telemetry" type="transparent">
|
||||
<configure name="MODEM_BAUD" value="B115200"/>
|
||||
</module>
|
||||
|
||||
<module name="actuators" type="uavcan">
|
||||
<configure name="UAVCAN_USE_CAN1" value="TRUE"/>
|
||||
<configure name="UAVCAN_USE_CAN2" value="TRUE"/>
|
||||
</module>
|
||||
<module name="actuators" type="pwm"/>
|
||||
<module name="imu" type="mpu6000"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<module name="stabilization" type="indi_simple"/>
|
||||
<module name="stabilization" type="rate_indi"/>
|
||||
<module name="ins" type="ekf2" />
|
||||
|
||||
<module name="air_data"/>
|
||||
<module name="send_imu_mag_current"/>
|
||||
|
||||
<!-- Internal MAG -->
|
||||
<!--module name="mag_ist8310">
|
||||
<define name="MODULE_IST8310_UPDATE_AHRS" value="TRUE"/>
|
||||
<configure name="MAG_IST8310_I2C_DEV" value="I2C3"/>
|
||||
</module-->
|
||||
<!-- External MAG on GPS -->
|
||||
<module name="mag_lis3mdl">
|
||||
<define name="MODULE_LIS3MDL_UPDATE_AHRS" value="TRUE"/>
|
||||
<configure name="MAG_LIS3MDL_I2C_DEV" value="I2C1"/>
|
||||
<define name="LIS3MDL_CHAN_X_SIGN" value="-"/>
|
||||
<define name="LIS3MDL_CHAN_Y_SIGN" value="-"/>
|
||||
</module>
|
||||
<!--module name="lidar" type="tfmini">
|
||||
<configure name="TFMINI_PORT" value="UART4"/>
|
||||
<configure name="USE_TFMINI_AGL" value="FALSE"/>
|
||||
</module-->
|
||||
|
||||
<module name="guidance" type="indi_hybrid">
|
||||
<define name="GUIDANCE_INDI_RC_DEBUG" value="FALSE"/>
|
||||
<define name="GUIDANCE_INDI_POS_GAIN" value="0.2"/>
|
||||
<define name="GUIDANCE_INDI_SPEED_GAIN" value="1.0"/>
|
||||
<define name="GUIDANCE_INDI_POS_GAINZ" value="0.2"/>
|
||||
<define name="GUIDANCE_INDI_SPEED_GAINZ" value="1.0"/>
|
||||
<define name="GUIDANCE_INDI_PITCH_LIFT_EFF" value="0.12"/>
|
||||
<define name="GUIDANCE_INDI_PITCH_EFF_SCALING" value="1.0"/>
|
||||
<define name="GUIDANCE_H_REF_MAX_SPEED" value="18.0"/> <!--not used-->
|
||||
<define name="GUIDANCE_INDI_MAX_AIRSPEED" value="16.0"/>
|
||||
<define name="GUIDANCE_HEADING_IS_FREE" value="FALSE"/> <!--heading can not be set by navigation-->
|
||||
<define name="GUIDANCE_INDI_HEADING_BANK_GAIN" value="5"/>
|
||||
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-943.0"/>
|
||||
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN_45" value="-500.0"/>
|
||||
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN_FWD" value="-1600.0"/>
|
||||
<define name="GUIDANCE_INDI_FILTER_CUTOFF" value="0.5"/>
|
||||
<define name="GUIDANCE_INDI_LINE_GAIN" value="0.2"/>
|
||||
<define name="GUIDANCE_INDI_MIN_THROTTLE" value="2500"/>
|
||||
</module>
|
||||
|
||||
<module name="motor_mixing"/>
|
||||
</firmware>
|
||||
|
||||
<!-- CAN BUS 1 (Front Wing) -->
|
||||
<servos driver="Pwm">
|
||||
<servo name="MOTOR_1" no="0" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_2" no="1" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_3" no="2" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_4" no="3" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_5" no="4" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_6" no="5" min="1000" neutral="1100" max="2000"/>
|
||||
<servo name="MOTOR_7" no="6" min="1000" neutral="1100" max="2000"/>
|
||||
</servos>
|
||||
|
||||
<!-- CAN BUS 1 (Front Wing) -->
|
||||
<servos driver="Uavcan1">
|
||||
<!--servo name="MOTOR_1" no="0" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_2" no="1" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_3" no="2" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_4" no="3" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_5" no="4" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_6" no="5" min="-8191" neutral="1500" max="8191"/-->
|
||||
<servo name="AIL_1" no="6" min="6000" neutral="0" max="-6000"/>
|
||||
<servo name="FLAP_1" no="7" min="6000" neutral="0" max="-6000"/>
|
||||
<servo name="FLAP_2" no="8" min="-6000" neutral="0" max="6000"/>
|
||||
<servo name="AIL_2" no="9" min="-6000" neutral="0" max="6000"/>
|
||||
</servos>
|
||||
|
||||
<servos driver="Uavcan2">
|
||||
<!--servo name="MOTOR_1" no="0" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_2" no="1" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_3" no="2" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_4" no="3" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_5" no="4" min="-8191" neutral="1500" max="8191"/>
|
||||
<servo name="MOTOR_6" no="5" min="-8191" neutral="1500" max="8191"/-->
|
||||
<servo name="AIL1_1" no="6" min="6000" neutral="0" max="-6000"/>
|
||||
<servo name="FLAP1_1" no="7" min="6000" neutral="0" max="-6000"/>
|
||||
<servo name="FLAP1_2" no="8" min="-6000" neutral="0" max="6000"/>
|
||||
<servo name="AIL1_2" no="9" min="-6000" neutral="0" max="6000"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="-300"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THRUST" value="@THROTTLE" />
|
||||
<set command="ROLL" value="@YAW" />
|
||||
<set command="PITCH" value="@PITCH/2" />
|
||||
<set command="YAW" value="-@ROLL/4" />
|
||||
</rc_commands>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
<!-- frontleft left (CCW), frontleft mid (CW), frontleft right (CCW), frontright left (CW), frontright mid (CCW), frontright right (CW) -->
|
||||
<!-- backleft left (CW), backleft mid (CCW), backleft right (CW), backright left (CCW), backright mid (CW), backright right (CCW) -->
|
||||
<define name="NB_MOTOR" value="12"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<define name="ROLL_COEF" value="{256, 157, 56, -56, -157, -256, 256, 157, 56, -56, -157, -256}"/>
|
||||
<define name="PITCH_COEF" value="{256, 256, 256, 256, 256, 256, -256, -256, -256, -256, -256, -256}"/>
|
||||
<define name="YAW_COEF" value="{256, -256, 256, -256, 256, -256, -256, 256, -256, 256, -256, 256}"/>
|
||||
<!--<define name="YAW_COEF" value="{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}"/>-->
|
||||
<define name="THRUST_COEF" value="{256, 256, 256, 256, 256, 256, 256, 256, 256, 256, 256, 256}"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
||||
<let var="th_hold" value="LessThan(RadioControlValues(RADIO_TH_HOLD), -4800)"/>
|
||||
|
||||
<set servo="MOTOR_1" value="($th_hold? -9600 : motor_mixing.commands[0])"/>
|
||||
<set servo="MOTOR_2" value="($th_hold? -9600 : motor_mixing.commands[1])"/>
|
||||
<set servo="MOTOR_3" value="($th_hold? -9600 : motor_mixing.commands[2])"/>
|
||||
<set servo="MOTOR_4" value="($th_hold? -9600 : motor_mixing.commands[3])"/>
|
||||
<set servo="MOTOR_5" value="($th_hold? -9600 : motor_mixing.commands[4])"/>
|
||||
<set servo="MOTOR_6" value="($th_hold? -9600 : motor_mixing.commands[5])"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="MISC">
|
||||
<!--define name="VoltageOfAdc(adc)" value="((3.3f/4096.0f) * 18.9040120162 * adc)"/--><!-- TODO: verify/calibrate -->
|
||||
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
|
||||
|
||||
<!-- Basic navigation settings -->
|
||||
<define name="NAV_CLIMB_VSPEED" value="3.5"/>
|
||||
<define name="NAV_DESCEND_VSPEED" value="-0.5"/>
|
||||
<define name="ARRIVED_AT_WAYPOINT" value="50.0"/>
|
||||
|
||||
<!-- Avoid GPS loss behavior when having RC or datalink -->
|
||||
<define name="NO_GPS_LOST_WITH_DATALINK_TIME" value="20"/>
|
||||
<define name="NO_GPS_LOST_WITH_RC_VALID" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="FORWARD">
|
||||
<!--The Nederdrone uses a slightly different axis system for the setpoint, to make both hovering and flying forward intuitive-->
|
||||
<define name="USE_EARTH_BOUND_RC_SETPOINT" value="TRUE"/>
|
||||
<!-- This is the pitch angle that the Nederdrone will have in forward flight, where 0 degrees is hover-->
|
||||
<define name="TRANSITION_MAX_OFFSET" value="-80.0" unit="deg"/>
|
||||
<!-- For RC coordinated turns, lower because the yawing was too slow -->
|
||||
<define name="MAX_FWD_SPEED" value="20.0"/>
|
||||
<!-- For hybrid guidance -->
|
||||
<define name="MAX_AIRSPEED" value="20.0"/>
|
||||
<!-- Enable airspeed measurements -->
|
||||
<define name="USE_AIRSPEED" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- Rotate the IMU (for Pixhawk 4) -->
|
||||
<define name="MPU_CHAN_X" value="1"/>
|
||||
<define name="MPU_CHAN_Y" value="0"/>
|
||||
<define name="MPU_CHAN_Z" value="2"/>
|
||||
<define name="MPU_X_SIGN" value="1"/>
|
||||
<define name="MPU_Y_SIGN" value="1"/>
|
||||
<define name="MPU_Z_SIGN" value="-1"/>
|
||||
|
||||
<!-- Calibrated 09-03-2021 in MAVLab outside body -->
|
||||
<define name="ACCEL_X_NEUTRAL" value="16"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="31"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="10"/>
|
||||
<define name="ACCEL_X_SENS" value="4.793311542012962" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="4.893892083504835" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="4.791159603565934" integer="16"/>
|
||||
|
||||
<!-- NOT CALIBRATED (internal magnetometer) -->
|
||||
<!--define name="MAG_X_NEUTRAL" value="-13"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-15"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="12"/>
|
||||
<define name="MAG_X_SENS" value="12.823826623678" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="12.86305350064853" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="12.512614596093622" integer="16"/-->
|
||||
|
||||
<!-- NOT CALIBRATED (external magnetometer) -->
|
||||
<define name="MAG_X_NEUTRAL" value="2457"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-1123"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="-1843"/>
|
||||
<define name="MAG_X_SENS" value="0.590610116730755" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="0.6411943049128617" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="0.6279536066632421" integer="16"/>
|
||||
|
||||
<!-- Define axis in hover frame -->
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="90." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="60." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="80." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="SP_PSI_DELTA_LIMIT" value="45" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
|
||||
<!-- control effectiveness (hover) -->
|
||||
<define name="G1_P" value="0.0030"/>
|
||||
<define name="G1_Q" value="0.0035"/>
|
||||
<define name="G1_R" value="0.0004"/>
|
||||
<define name="G2_R" value="0.00015"/>
|
||||
|
||||
<!-- control effectiveness (forward) -->
|
||||
<define name="FORWARD_G1_P" value="0.0020"/>
|
||||
<define name="FORWARD_G1_Q" value="0.0077"/>
|
||||
<define name="FORWARD_G1_R" value="0.004"/>
|
||||
|
||||
<!-- reference acceleration for attitude control -->
|
||||
<define name="REF_ERR_P" value="30.0"/>
|
||||
<define name="REF_ERR_Q" value="30.0"/>
|
||||
<define name="REF_ERR_R" value="20.0"/>
|
||||
<define name="REF_RATE_P" value="6.0"/>
|
||||
<define name="REF_RATE_Q" value="6.0"/>
|
||||
<define name="REF_RATE_R" value="6.0"/>
|
||||
|
||||
<!--Maxium yaw rate, to avoid instability-->
|
||||
<define name="MAX_R" value="50.0" unit="deg/s"/>
|
||||
|
||||
<!-- Maximum rate setpoint in rate control mode -->
|
||||
<define name="MAX_RATE" value="3.0" unit="rad/s"/>
|
||||
|
||||
<!-- second order filter parameters -->
|
||||
<define name="FILT_CUTOFF" value="1.5"/>
|
||||
<define name="FILT_CUTOFF_RDOT" value="0.5"/>
|
||||
<define name="ESTIMATION_FILT_CUTOFF" value="5.0"/>
|
||||
<define name="FILT_CUTOFF_R" value="4.0"/>
|
||||
|
||||
<!-- first order actuator dynamics -->
|
||||
<define name="ACT_DYN_P" value="0.0354"/>
|
||||
<define name="ACT_DYN_Q" value="0.0354"/>
|
||||
<define name="ACT_DYN_R" value="0.0354"/>
|
||||
|
||||
<!-- Adaptive Learning Rate -->
|
||||
<define name="USE_ADAPTIVE" value="FALSE"/>
|
||||
<define name="ADAPTIVE_MU" value="0.0001"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="HOVER_KP" value="310"/>
|
||||
<define name="HOVER_KD" value="130"/>
|
||||
<define name="HOVER_KI" value="10"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.42"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="30" unit="deg"/>
|
||||
<define name="USE_SPEED_REF" value="TRUE"/>
|
||||
<define name="PGAIN" value="60"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="AGAIN" value="0"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="m1,m2,m3,m4,m5,m6,m7,m8,m9,m10,m11,m12,ail1,ail2,ail3,ail4,flap1,flap2,flap3,flap4" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="nederdrone" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_FORWARD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="18.0" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="18.6" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="19.2" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="25.2" unit="V"/>
|
||||
<define name="BAT_NB_CELLS" value="4"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -1,216 +0,0 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- this is a quadrotor frame in X-configuration equiped with
|
||||
* Autopilot: Navstik http://wiki.paparazziuav.org/wiki/Navstik
|
||||
* IMU: Navstik http://wiki.paparazziuav.org/wiki/Navstik
|
||||
* Actuators: Asctec V2 http://wiki.paparazziuav.org/wiki/Subsystem/actuators#Asctec_v2
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: one Spektrum sat http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#Spektrum
|
||||
-->
|
||||
|
||||
<airframe name="Quadrotor Navstik">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="navstik_1.0">
|
||||
<configure name="ACTUATORS_ASCTEC_V2_I2C_DEV" value="i2c3"/>
|
||||
<define name="ACTUATORS_START_DELAY" value="1"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<module name="fdm" type="jsbsim"/>
|
||||
</target>
|
||||
|
||||
<module name="radio_control" type="spektrum">
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
|
||||
<define name="RADIO_MODE" value="RADIO_AUX1"/>
|
||||
</module>
|
||||
<module name="motor_mixing"/>
|
||||
<module name="actuators" type="asctec_v2"/>
|
||||
<module name="telemetry" type="xbee_api"/>
|
||||
<module name="imu" type="navstik"/>
|
||||
<module name="gps" type="ublox"/>
|
||||
<module name="stabilization" type="indi_simple"/>
|
||||
<module name="ahrs" type="int_cmpl_quat"/>
|
||||
<module name="ins" type="hff"/>
|
||||
|
||||
<module name="gps" type="ubx_ucenter"/>
|
||||
<!--module name="airspeed_ms45xx_i2c">
|
||||
<configure name="MS45XX_I2C_DEV" value="i2c3"/>
|
||||
</module>
|
||||
<module name="direct_memory_logger"/-->
|
||||
</firmware>
|
||||
|
||||
<firmware name="test_progs">
|
||||
<configure name="MODEM_PORT" value="UART1"/>
|
||||
|
||||
<target name="test_sys_time_timer" board="navstik_1.0"/>
|
||||
<target name="test_telemetry" board="navstik_1.0"/>
|
||||
<target name="test_actuators_pwm_sin" board="navstik_1.0"/>
|
||||
</firmware>
|
||||
|
||||
<servos driver="Asctec_v2">
|
||||
<servo name="FRONT" no="0" min="0" neutral="3" max="200"/>
|
||||
<servo name="BACK" no="1" min="0" neutral="3" max="200"/>
|
||||
<servo name="LEFT" no="2" min="0" neutral="3" max="200"/>
|
||||
<servo name="RIGHT" no="3" min="0" neutral="3" max="200"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
<define name="TRIM_ROLL" value="0"/>
|
||||
<define name="TRIM_PITCH" value="0"/>
|
||||
<define name="TRIM_YAW" value="0"/>
|
||||
<define name="NB_MOTOR" value="4"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<!-- order (and rotation direction) : NE (CW), SE (CCW), SW (CW), NW (CCW) -->
|
||||
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
|
||||
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
|
||||
<define name="YAW_COEF" value="{ -256, 256, -256, 256 }"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[0]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[1]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[2]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[3]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="11"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="11"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-25"/>
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="-179"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-21"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="79"/>
|
||||
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.40442339014" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="H_X" value="0.3770441"/>
|
||||
<define name="H_Y" value="0.0193986"/>
|
||||
<define name="H_Z" value="0.9259921"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
|
||||
<!-- control effectiveness -->
|
||||
<define name="G1_P" value="0.150"/>
|
||||
<define name="G1_Q" value="0.150"/>
|
||||
<define name="G1_R" value="0.005119"/>
|
||||
<define name="G2_R" value="0.2166"/>
|
||||
|
||||
<!-- reference acceleration for attitude control -->
|
||||
<define name="REF_ERR_P" value="900.0"/>
|
||||
<define name="REF_ERR_Q" value="900.0"/>
|
||||
<define name="REF_ERR_R" value="500.0"/>
|
||||
<define name="REF_RATE_P" value="38.0"/>
|
||||
<define name="REF_RATE_Q" value="38.0"/>
|
||||
<define name="REF_RATE_R" value="25.0"/>
|
||||
|
||||
<!-- second order filter parameters -->
|
||||
<define name="FILT_CUTOFF" value="8.0"/>
|
||||
|
||||
<!-- first order actuator dynamics -->
|
||||
<define name="ACT_DYN_P" value="0.2"/>
|
||||
<define name="ACT_DYN_Q" value="0.2"/>
|
||||
<define name="ACT_DYN_R" value="0.2"/>
|
||||
|
||||
<!-- Adaptive Learning Rate -->
|
||||
<define name="USE_ADAPTIVE" value="FALSE"/>
|
||||
<define name="ADAPTIVE_MU" value="0.0001"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(7000.)"/>
|
||||
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="300." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(7000.)"/>
|
||||
<define name="REF_OMEGA_R" value="500" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.85"/>
|
||||
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="900"/>
|
||||
<define name="PHI_DGAIN" value="200"/>
|
||||
<define name="PHI_IGAIN" value="200"/>
|
||||
<define name="THETA_PGAIN" value="900"/>
|
||||
<define name="THETA_DGAIN" value="200"/>
|
||||
<define name="THETA_IGAIN" value="200"/>
|
||||
<define name="PSI_PGAIN" value="900"/>
|
||||
<define name="PSI_DGAIN" value="200"/>
|
||||
<define name="PSI_IGAIN" value="10"/>
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="75"/>
|
||||
<define name="THETA_DDGAIN" value="75"/>
|
||||
<define name="PSI_DDGAIN" value="75"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_Z" value="POS_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MIN_ERR_ZD" value="SPEED_BFP_OF_REAL(-10.)"/>
|
||||
<define name="MAX_ERR_ZD" value="SPEED_BFP_OF_REAL( 10.)"/>
|
||||
<define name="MAX_SUM_ERR" value="2000000"/>
|
||||
<define name="HOVER_KP" value="150"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.5"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="20" unit="deg"/>
|
||||
<define name="USE_SPEED_REF" value="TRUE"/>
|
||||
<define name="PGAIN" value="50"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="AGAIN" value="70"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="ne_motor, se_motor, sw_motor, nw_motor" type="string[]"/>
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad" type="string"/>
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="10.1" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -17,7 +17,7 @@ RTOS=chibios
|
||||
## FPU on F4
|
||||
USE_FPU=softfp
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
|
||||
@@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
USE_LTO ?= yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -33,7 +33,6 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@ ARCH=chibios
|
||||
## FPU on F4
|
||||
USE_FPU=softfp
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
|
||||
@@ -0,0 +1,88 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# cube_orange.makefile
|
||||
#
|
||||
# This is for the main MCU (STM32F767) on the PX4 board
|
||||
# See https://pixhawk.org/modules/pixhawk for details
|
||||
#
|
||||
|
||||
BOARD=cube
|
||||
BOARD_VERSION=orange
|
||||
BOARD_DIR=$(BOARD)/$(BOARD_VERSION)
|
||||
BOARD_CFG=\"arch/chibios/common_board.h\"
|
||||
|
||||
ARCH=chibios
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
RTOS=chibios
|
||||
MCU=cortex-m7
|
||||
|
||||
# FPU on F7
|
||||
USE_FPU=hard
|
||||
USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
#USE_LTO=yes
|
||||
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
#
|
||||
# Define project name here (target)
|
||||
PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32H7xx/platform.mk
|
||||
CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/
|
||||
CHIBIOS_BOARD_LINKER = STM32H743xI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32h7xx.mk
|
||||
|
||||
##############################################################################
|
||||
# Compiler settings
|
||||
#
|
||||
|
||||
# default flash mode is the PX4 bootloader
|
||||
# possibilities: DFU, SWD, PX4 bootloader
|
||||
FLASH_MODE ?= PX4_BOOTLOADER
|
||||
PX4_TARGET = "ap"
|
||||
PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/cube_orange.prototype"
|
||||
PX4_BL_PORT ?= "/dev/serial/by-id/usb-Hex_ProfiCNC_CubeOrange*-BL*"
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
SDLOG_LED ?= none
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= 1
|
||||
|
||||
#
|
||||
# default UART configuration (modem, gps, spektrum)
|
||||
# The TELEM2 port
|
||||
SBUS_PORT ?= UART3
|
||||
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART3
|
||||
|
||||
# The TELEM1 port (UART3 is TELEM2)
|
||||
MODEM_PORT ?= UART2
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
# The GPS1 port (UART8 is GPS2)
|
||||
GPS_PORT ?= UART1
|
||||
GPS_BAUD ?= B57600
|
||||
|
||||
# InterMCU port connected to the IO processor
|
||||
INTERMCU_PORT ?= UART6
|
||||
INTERMCU_BAUD ?= B230400
|
||||
|
||||
#
|
||||
# default actuator configuration
|
||||
#
|
||||
# you can use different actuators by adding a configure option to your firmware section
|
||||
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
|
||||
# and by setting the correct "driver" attribute in servo section
|
||||
# e.g. <servo driver="Ppm">
|
||||
#
|
||||
ACTUATORS ?= actuators_pwm
|
||||
|
||||
@@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-sp-d16
|
||||
|
||||
USE_LTO ?= yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -33,7 +33,6 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
#CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_LINKER = STM32F746xG.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
@@ -15,7 +15,7 @@ RTOS=chibios
|
||||
USE_FPU=no
|
||||
HARD_FLOAT=no
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F1 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
|
||||
@@ -20,7 +20,7 @@ USE_FPU=hard
|
||||
# See list of supported Tier 3 architectures at: https://forge.rust-lang.org/platform-support.html
|
||||
RUST_ARCH = thumbv7em-none-eabihf
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
|
||||
@@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
USE_LTO ?= yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -33,7 +33,6 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
|
||||
@@ -1,54 +0,0 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# navstik_1.0.makefile
|
||||
#
|
||||
# http://wiki.paparazziuav.org/wiki/Navstik
|
||||
#
|
||||
|
||||
BOARD=navstik
|
||||
BOARD_VERSION=1.0
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
ARCH=stm32
|
||||
ARCH_L=f4
|
||||
HARD_FLOAT=yes
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
$(TARGET).OOCD_INTERFACE=ftdi/ivygs
|
||||
$(TARGET).OOCD_BOARD=navstik
|
||||
$(TARGET).LDSCRIPT=$(SRC_ARCH)/navstik.ld
|
||||
|
||||
# -----------------------------------------------------------------------
|
||||
|
||||
# default flash mode is via usb dfu bootloader
|
||||
# other possibilities: DFU-UTIL, JTAG
|
||||
FLASH_MODE ?= JTAG
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= 2
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= 1
|
||||
|
||||
#
|
||||
# default uart configuration
|
||||
#
|
||||
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART6
|
||||
|
||||
MODEM_PORT ?= UART5
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
GPS_PORT ?= UART2
|
||||
GPS_BAUD ?= B57600
|
||||
|
||||
#
|
||||
# default actuator configuration
|
||||
#
|
||||
# you can use different actuators by adding a configure option to your firmware section
|
||||
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
|
||||
# and by setting the correct "driver" attribute in servo section
|
||||
# e.g. <servo driver="Ppm">
|
||||
#
|
||||
ACTUATORS ?= actuators_pwm
|
||||
@@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
USE_LTO=yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -33,7 +33,6 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
|
||||
@@ -19,7 +19,7 @@ RTOS=chibios
|
||||
# FPU on F4
|
||||
USE_FPU=hard
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -32,14 +32,6 @@ CHIBIOS_BOARD_PLATFORM = STM32F4xx/platform.mk
|
||||
CHIBIOS_BOARD_LINKER = STM32F407xG.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f4xx.mk
|
||||
|
||||
# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order
|
||||
# to correctly initialize the interrupt vector we have to define that
|
||||
# the board has LUFTBOOT
|
||||
HAS_LUFTBOOT ?= 1
|
||||
ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE))
|
||||
$(TARGET).CFLAGS+=-DLUFTBOOT
|
||||
endif
|
||||
|
||||
##############################################################################
|
||||
# Compiler settings
|
||||
#
|
||||
|
||||
@@ -15,11 +15,12 @@ ARCH=chibios
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
RTOS=chibios
|
||||
MCU=cortex-m4
|
||||
|
||||
# FPU on F4
|
||||
USE_FPU=hard
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F4 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -29,21 +30,13 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F4xx/platform.mk
|
||||
CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/
|
||||
CHIBIOS_BOARD_LINKER = STM32F427xT.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f4xx.mk
|
||||
|
||||
# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order
|
||||
# to correctly initialize the interrupt vector we have to define that
|
||||
# the board has LUFTBOOT
|
||||
HAS_LUFTBOOT ?= 1
|
||||
ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE))
|
||||
$(TARGET).CFLAGS+=-DLUFTBOOT
|
||||
endif
|
||||
|
||||
##############################################################################
|
||||
# Compiler settings
|
||||
#
|
||||
MCU = cortex-m4
|
||||
|
||||
# default flash mode is the PX4 bootloader
|
||||
# possibilities: DFU, SWD, PX4 bootloader
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
BOARD=px4fmu
|
||||
BOARD_VERSION=5.0
|
||||
BOARD_DIR=$(BOARD)/chibios/v$(BOARD_VERSION)
|
||||
BOARD_CFG=\"boards/$(BOARD_DIR)/$(BOARD).h\"
|
||||
BOARD_CFG=\"arch/chibios/common_board.h\"
|
||||
|
||||
ARCH=chibios
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
@@ -23,7 +23,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
#USE_LTO=yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -33,30 +33,10 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/
|
||||
CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
# ITCM flash is a special flash that allow faster operations
|
||||
# At the moment it is not possible to flash the code in this mode using dfu-util
|
||||
# but it should work with the BlackMagicProbe or STLINK
|
||||
# By default, normal flash is used
|
||||
ifeq ($(USE_ITCM),1)
|
||||
$(TARGET).CFLAGS += -DUSE_ITCM=1
|
||||
DFU_ADDR = 0x00200000
|
||||
else
|
||||
$(TARGET).CFLAGS += -DUSE_ITCM=0
|
||||
DFU_ADDR = 0x08000000
|
||||
endif
|
||||
|
||||
# In this case we dont have LUFTBOOT but PX4_BOOTLOADER, but in order
|
||||
# to correctly initialize the interrupt vector we have to define that
|
||||
# the board has LUFTBOOT
|
||||
HAS_LUFTBOOT ?= 1
|
||||
ifeq (,$(findstring $(HAS_LUFTBOOT),0 FALSE))
|
||||
$(TARGET).CFLAGS+=-DLUFTBOOT
|
||||
endif
|
||||
|
||||
##############################################################################
|
||||
# Compiler settings
|
||||
#
|
||||
|
||||
@@ -22,7 +22,7 @@ USE_FPU_OPT= -mfpu=fpv5-d16
|
||||
|
||||
USE_LTO ?= yes
|
||||
|
||||
$(TARGET).CFLAGS += -DSTM32F7 -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD -DDSHOT_CHANNEL_FIRST_INDEX=1U
|
||||
|
||||
##############################################################################
|
||||
# Architecture or project specific options
|
||||
@@ -32,7 +32,6 @@ PROJECT = $(TARGET)
|
||||
|
||||
# Project specific files and paths (see Makefile.chibios for details)
|
||||
CHIBIOS_BOARD_PLATFORM = STM32F7xx/platform.mk
|
||||
CHIBIOS_BOARD_PORT = ARMCMx/STM32F7xx/port.mk
|
||||
CHIBIOS_BOARD_LINKER = STM32F76xxI.ld
|
||||
CHIBIOS_BOARD_STARTUP = startup_stm32f7xx.mk
|
||||
|
||||
|
||||
+13
-24
@@ -7,7 +7,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/nav_basic_fw.xml modules/gps.xml modules/ahrs_float_dcm.xml modules/imu_common.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -18,7 +18,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +29,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/radio_control_superbitrf_rc.xml modules/gps_ubx_ucenter.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -40,7 +40,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
|
||||
flight_plan="flight_plans/versatile_airspeed.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
|
||||
settings_modules="modules/digital_cam.xml modules/light.xml modules/gps_ubx_ucenter.xml modules/geo_mag.xml modules/air_data.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_energy.xml modules/stabilization_attitude_fw.xml modules/ahrs_int_cmpl_quat.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#ffffffffffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -51,7 +51,7 @@
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules=""
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -62,7 +62,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +73,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_rate.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -84,20 +84,9 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
name="Quad_Navstik"
|
||||
ac_id="24"
|
||||
airframe="airframes/examples/quadrotor_navstik.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="#710080"
|
||||
/>
|
||||
<aircraft
|
||||
name="ardrone2"
|
||||
ac_id="31"
|
||||
@@ -106,7 +95,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/geo_mag.xml modules/air_data.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -117,7 +106,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -128,7 +117,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/cv_opticflow.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/bebop_cam.xml modules/cv_opticflow.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -139,7 +128,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/guidance_hybrid.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/guidance_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -150,7 +139,7 @@
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/dummy.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="[modules/gps.xml] [modules/ahrs_float_cmpl_quat.xml] [modules/ins_extended.xml] [modules/stabilization_int_quat.xml] [modules/nav_basic_rotorcraft.xml] [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] modules/radio_control_cc2500_frsky.xml"
|
||||
settings_modules="[modules/ahrs_float_cmpl_quat.xml] [modules/gps.xml] [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] [modules/ins_extended.xml] [modules/nav_basic_rotorcraft.xml] modules/radio_control_cc2500_frsky.xml [modules/stabilization_int_quat.xml]"
|
||||
gui_color="blue"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
+38
-27
@@ -1,4 +1,15 @@
|
||||
<conf>
|
||||
<aircraft
|
||||
name="CubeOrange"
|
||||
ac_id="1"
|
||||
airframe="airframes/examples/cube_orange.xml"
|
||||
radio="radios/crossfire_sbus.xml"
|
||||
telemetry="telemetry/highspeed_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="DualBoard_AP_FBW"
|
||||
ac_id="3"
|
||||
@@ -7,7 +18,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/air_data.xml modules/nav_catapult.xml modules/digital_cam.xml modules/light.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -18,7 +29,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml"
|
||||
settings_modules="modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/gps.xml"
|
||||
settings_modules="modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +40,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -40,29 +51,7 @@
|
||||
telemetry="telemetry/fixedwing_flight_recorder.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/ahrs_float_dcm.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="bebop2_opticflow"
|
||||
ac_id="32"
|
||||
airframe="airframes/examples/bebop2_opticflow.xml"
|
||||
radio="radios/cockpitSX.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/bebop_cam.xml modules/cv_opticflow.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="quad_mavlink"
|
||||
ac_id="36"
|
||||
airframe="airframes/examples/quadrotor_lisa_mx_mavlink.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +62,29 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_optitrack.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.xml modules/cv_opticflow.xml modules/geo_mag.xml modules/air_data.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/cv_colorfilter.xml modules/cv_opticflow.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
name="bebop2_opticflow"
|
||||
ac_id="32"
|
||||
airframe="airframes/examples/bebop2_opticflow.xml"
|
||||
radio="radios/cockpitSX.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/bebop_cam.xml modules/cv_opticflow.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="quad_mavlink"
|
||||
ac_id="36"
|
||||
airframe="airframes/examples/quadrotor_lisa_mx_mavlink.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/lidar_lite.xml modules/gps.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml"
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="#ffff954c0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -18,7 +18,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/nav_basic_fw.xml modules/gps.xml modules/ahrs_float_dcm.xml modules/imu_common.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -29,7 +29,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/gps_ubx_ucenter.xml modules/gps.xml modules/air_data.xml modules/nav_catapult.xml modules/digital_cam.xml modules/light.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -40,7 +40,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_full_pid_fw.xml modules/stabilization_adaptive_fw.xml modules/airspeed_adc.xml modules/imu_common.xml modules/ahrs_float_dcm.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/airspeed_adc.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_full_pid_fw.xml modules/imu_common.xml modules/ins_float_invariant.xml modules/nav_basic_fw.xml modules/stabilization_adaptive_fw.xml"
|
||||
gui_color="#ffff7d7d0000"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -51,7 +51,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/superbitrf.xml settings/nps.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/radio_control_superbitrf_rc.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -62,7 +62,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,7 +73,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu_9k6.xml"
|
||||
flight_plan="flight_plans/versatile_airspeed.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/ac_char.xml"
|
||||
settings_modules="modules/digital_cam.xml modules/light.xml modules/gps_ubx_ucenter.xml modules/geo_mag.xml modules/air_data.xml modules/gps.xml modules/nav_basic_fw.xml modules/guidance_energy.xml modules/stabilization_attitude_fw.xml modules/ahrs_int_cmpl_quat.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/digital_cam.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_energy.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#ffffffffffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -84,7 +84,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/nav_modules.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml settings/nps.xml"
|
||||
settings_modules="modules/nav_survey_poly_osam.xml modules/nav_smooth.xml modules/air_data.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/nav_smooth.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -95,7 +95,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/gps.xml modules/ahrs_int_cmpl_quat.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -106,7 +106,7 @@
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_dash_loiter_trim.xml"
|
||||
settings_modules="modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/gps.xml"
|
||||
settings_modules="modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -117,7 +117,7 @@
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/AGGIEAIR/BasicTuning_Launcher.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/nps.xml"
|
||||
settings_modules=""
|
||||
settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/lidar_sf11.xml modules/nav_basic_fw.xml modules/nav_skid_landing.xml modules/nav_survey_poly_osam.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="#00009e93ffff"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -128,7 +128,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -139,7 +139,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_rate.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/stabilization_rate.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -150,20 +150,9 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="white"
|
||||
/>
|
||||
<aircraft
|
||||
name="Quad_Navstik"
|
||||
ac_id="24"
|
||||
airframe="airframes/examples/quadrotor_navstik.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
gui_color="#710080"
|
||||
/>
|
||||
<aircraft
|
||||
name="Quad_Revolution"
|
||||
ac_id="43"
|
||||
@@ -172,7 +161,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/gps_ubx_ucenter.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -183,7 +172,7 @@
|
||||
telemetry="telemetry/fixedwing_flight_recorder.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml"
|
||||
settings_modules="modules/gps.xml modules/nav_basic_fw.xml modules/guidance_basic_fw.xml modules/stabilization_attitude_fw.xml modules/ahrs_float_dcm.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -194,7 +183,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/geo_mag.xml modules/air_data.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -205,7 +194,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/opticflow_hover.xml modules/cv_opticflow.xml modules/gps_ubx_ucenter.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/cv_opticflow.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/opticflow_hover.xml modules/stabilization_int_quat.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -216,7 +205,7 @@
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/nps.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
|
||||
settings_modules="modules/ahrs_float_mlkf.xml modules/air_data.xml modules/bebop_ae_awb.xml modules/bebop_cam.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml modules/video_rtp_stream.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
</conf>
|
||||
|
||||
@@ -14,13 +14,6 @@ ifeq ($(BOARD), lisa_l)
|
||||
BARO_BOARD_CFLAGS += -DUSE_I2C2
|
||||
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c
|
||||
|
||||
# Navstik baro
|
||||
else ifeq ($(BOARD), navstik)
|
||||
BARO_BOARD_CFLAGS += -DUSE_I2C3
|
||||
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_BOARD_BMP085
|
||||
BARO_BOARD_SRCS += peripherals/bmp085.c
|
||||
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c
|
||||
|
||||
# Ardrone baro
|
||||
else ifeq ($(BOARD), ardrone)
|
||||
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c
|
||||
|
||||
@@ -124,9 +124,6 @@ ifeq ($(BOARD_VERSION), 2.0)
|
||||
LED_DEFINES = -DLED_BLUE=3 -DLED_RED=4 -DLED_GREEN=5
|
||||
endif
|
||||
endif
|
||||
ifeq ($(BOARD), navstik)
|
||||
LED_DEFINES = -DLED_RED=1 -DLED_GREEN=2
|
||||
endif
|
||||
ifeq ($(BOARD), cc3d)
|
||||
LED_DEFINES = -DLED_BLUE=1
|
||||
endif
|
||||
|
||||
@@ -27,7 +27,6 @@
|
||||
<boards>
|
||||
<board name="apogee_.*"/>
|
||||
<board name="li[s]?a_mx_.*"/>
|
||||
<board name="navstik_.*"/>
|
||||
<board name="elle*"/>
|
||||
<board name="openpilot_revo.*"/>
|
||||
<board name="chimera_.*"/>
|
||||
@@ -77,6 +76,7 @@
|
||||
<board name="nucleo.*"/>
|
||||
<board name="matek_.*"/>
|
||||
<board name="holybro_.*"/>
|
||||
<board name="cube_.*"/>
|
||||
</boards>
|
||||
</mode>
|
||||
<mode name="BlackMagic Probe (SWD_NOPWR)">
|
||||
@@ -103,6 +103,7 @@
|
||||
<boards>
|
||||
<board name="px4fmu_.*"/>
|
||||
<board name="px4io_.*"/>
|
||||
<board name="cube_.*"/>
|
||||
</boards>
|
||||
</mode>
|
||||
<mode name="JTAG (OpenOCD)">
|
||||
@@ -110,7 +111,6 @@
|
||||
<boards>
|
||||
<board name="krooz_sd"/>
|
||||
<board name="li[s]?a_[lm]?_.*"/>
|
||||
<board name="navstik_.*"/>
|
||||
<board name="elle*"/>
|
||||
</boards>
|
||||
</mode>
|
||||
|
||||
@@ -17,16 +17,8 @@
|
||||
<raw>
|
||||
ifeq ($(USE_BARO_BOARD), TRUE)
|
||||
|
||||
# Navstik baro
|
||||
ifeq ($(BOARD), navstik)
|
||||
BARO_BOARD_CFLAGS += -DUSE_I2C3
|
||||
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_BOARD_BMP085
|
||||
BARO_BOARD_SRCS += peripherals/bmp085.c
|
||||
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c
|
||||
|
||||
|
||||
# Lisa/M baro
|
||||
else ifeq ($(BOARD), lisa_m)
|
||||
ifeq ($(BOARD), lisa_m)
|
||||
ifeq ($(BOARD_VERSION), 1.0)
|
||||
# on lisa_m_1.0: defaults to i2c baro bmp085 on the board
|
||||
LISA_M_BARO ?= BARO_BOARD_BMP085
|
||||
|
||||
@@ -0,0 +1,17 @@
|
||||
<!DOCTYPE module SYSTEM "../module.dtd">
|
||||
|
||||
<module name="cube_orange" dir="boards">
|
||||
<doc>
|
||||
<description>
|
||||
Specific configuration for Cube Orange with ChibiOS
|
||||
</description>
|
||||
</doc>
|
||||
<dep>
|
||||
<depends>spi_master,baro_ms5611_spi</depends>
|
||||
</dep>
|
||||
<makefile target="!sim|nps|fbw">
|
||||
<configure name="SDLOG_USE_RTC" value="FALSE"/>
|
||||
<configure name="MS5611_SPI_DEV" value="spi1"/> <!-- spi4 -->
|
||||
<configure name="MS5611_SLAVE_IDX" value="SPI_SLAVE6"/> <!-- SPI_SLAVE4 -->
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -1,14 +0,0 @@
|
||||
<!DOCTYPE module SYSTEM "../module.dtd">
|
||||
|
||||
<module name="navstik_1.0" dir="boards">
|
||||
<doc>
|
||||
<description>
|
||||
Specific configuration for Navstik 1.0
|
||||
</description>
|
||||
</doc>
|
||||
<dep>
|
||||
<depends>i2c,baro_board</depends>
|
||||
</dep>
|
||||
<makefile target="!sim|nps|fbw"/>
|
||||
</module>
|
||||
|
||||
@@ -9,6 +9,8 @@
|
||||
<dep>
|
||||
<depends>spi_master,baro_board</depends>
|
||||
</dep>
|
||||
<makefile target="!sim|nps|fbw"/>
|
||||
<makefile target="!sim|nps|fbw">
|
||||
<configure name="SDLOG_USE_RTC" value="FALSE"/>
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
|
||||
@@ -1,47 +0,0 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="imu_navstik" dir="imu" task="sensors">
|
||||
<doc>
|
||||
<description>
|
||||
Navstik IMU: MPU60x0 and HMC5883 via I2C.
|
||||
</description>
|
||||
<configure name="NAVSTIK_MAG_I2C_DEV" value="i2c3" description="I2C device to use for MAG"/>
|
||||
<configure name="NAVSTIK_MPU_I2C_DEV" value="i2c1" description="I2C device to use for MPU"/>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="MAG_X_NEUTRAL" value="2358"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="2362"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="2119"/>
|
||||
|
||||
<define name="MAG_X_SENS" value="3.4936416" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.607713" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.90788848" integer="16"/>
|
||||
</section>
|
||||
</doc>
|
||||
<dep>
|
||||
<depends>i2c,imu_common</depends>
|
||||
<provides>imu,mag</provides>
|
||||
</dep>
|
||||
<autoload name="imu_nps"/>
|
||||
<autoload name="imu_sim"/>
|
||||
<header>
|
||||
<file name="imu_navstik.h"/>
|
||||
</header>
|
||||
<init fun="imu_navstik_init()"/>
|
||||
<periodic fun="imu_navstik_periodic()"/>
|
||||
<event fun="imu_navstik_event()"/>
|
||||
<makefile target="!sim|nps|fbw">
|
||||
<configure name="NAVSTIK_MAG_I2C_DEV" default="i2c3" case="lower|upper"/>
|
||||
<define name="NAVSTIK_MAG_I2C_DEV" value="$(NAVSTIK_MAG_I2C_DEV_LOWER)"/>
|
||||
<define name="USE_$(NAVSTIK_MAG_I2C_DEV_UPPER)"/>
|
||||
<configure name="NAVSTIK_MPU_I2C_DEV" default="i2c1" case="lower|upper"/>
|
||||
<define name="NAVSTIK_MPU_I2C_DEV" value="$(NAVSTIK_MPU_I2C_DEV_LOWER)"/>
|
||||
<define name="USE_$(NAVSTIK_MPU_I2C_DEV_UPPER)"/>
|
||||
|
||||
<define name="IMU_TYPE_H" value="modules/imu/imu_navstik.h" type="string"/>
|
||||
|
||||
<file name="mpu60x0.c" dir="peripherals"/>
|
||||
<file name="mpu60x0_i2c.c" dir="peripherals"/>
|
||||
<file name="hmc58xx.c" dir="peripherals"/>
|
||||
<file name="imu_navstik.c"/>
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -300,7 +300,7 @@
|
||||
<aircraft
|
||||
name="Nederdrone5"
|
||||
ac_id="27"
|
||||
airframe="airframes/tudelft/nederdrone5.xml"
|
||||
airframe="airframes/tudelft/cube_test.xml"
|
||||
radio="radios/crossfire_sbus.xml"
|
||||
telemetry="telemetry/highspeed_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/nederdrone_valkenburg.xml"
|
||||
|
||||
@@ -0,0 +1,139 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
|
||||
|
||||
Licensed 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.
|
||||
*/
|
||||
|
||||
/*
|
||||
* STM32H743xI generic setup.
|
||||
*
|
||||
* AXI SRAM - BSS, Data, Heap.
|
||||
* SRAM1+SRAM2 - None.
|
||||
* SRAM3 - NOCACHE, ETH.
|
||||
* SRAM4 - None.
|
||||
* DTCM-RAM - Main Stack, Process Stack.
|
||||
* ITCM-RAM - None.
|
||||
* BCKP SRAM - None.
|
||||
*/
|
||||
MEMORY
|
||||
{
|
||||
flash0 (rx) : org = 0x08020000, len = 2M /* Flash bank1+bank2 */
|
||||
flash1 (rx) : org = 0x08020000, len = 1M /* Flash bank 1 */
|
||||
flash2 (rx) : org = 0x08100000, len = 1M /* Flash bank 2 */
|
||||
flash3 (rx) : org = 0x00000000, len = 0
|
||||
flash4 (rx) : org = 0x00000000, len = 0
|
||||
flash5 (rx) : org = 0x00000000, len = 0
|
||||
flash6 (rx) : org = 0x00000000, len = 0
|
||||
flash7 (rx) : org = 0x00000000, len = 0
|
||||
ram0 (wx) : org = 0x24000000, len = 64k /* AXI SRAM no-cache*/
|
||||
ram1 (wx) : org = 0x24010000, len = 448k /* AXI SRAM cached */
|
||||
ram2 (wx) : org = 0x30000000, len = 288k /* AHB SRAM1+SRAM2+SRAM3 */
|
||||
ram3 (wx) : org = 0x30040000, len = 32k /* AHB SRAM3 */
|
||||
ram4 (wx) : org = 0x38000000, len = 64k /* AHB SRAM4 */
|
||||
ram5 (wx) : org = 0x20000000, len = 128k /* DTCM-RAM */
|
||||
ram6 (wx) : org = 0x00000000, len = 64k /* ITCM-RAM */
|
||||
ram7 (wx) : org = 0x38800000, len = 4k /* BCKP SRAM */
|
||||
}
|
||||
|
||||
/* For each data/text section two region are defined, a virtual region
|
||||
and a load region (_LMA suffix).*/
|
||||
|
||||
/* Flash region to be used for exception vectors.*/
|
||||
REGION_ALIAS("VECTORS_FLASH", flash0);
|
||||
REGION_ALIAS("VECTORS_FLASH_LMA", flash0);
|
||||
|
||||
/* Flash region to be used for constructors and destructors.*/
|
||||
REGION_ALIAS("XTORS_FLASH", flash0);
|
||||
REGION_ALIAS("XTORS_FLASH_LMA", flash0);
|
||||
|
||||
/* Flash region to be used for code text.*/
|
||||
REGION_ALIAS("TEXT_FLASH", flash0);
|
||||
REGION_ALIAS("TEXT_FLASH_LMA", flash0);
|
||||
|
||||
/* Flash region to be used for read only data.*/
|
||||
REGION_ALIAS("RODATA_FLASH", flash0);
|
||||
REGION_ALIAS("RODATA_FLASH_LMA", flash0);
|
||||
|
||||
/* Flash region to be used for various.*/
|
||||
REGION_ALIAS("VARIOUS_FLASH", flash0);
|
||||
REGION_ALIAS("VARIOUS_FLASH_LMA", flash0);
|
||||
|
||||
/* Flash region to be used for RAM(n) initialization data.*/
|
||||
REGION_ALIAS("RAM_INIT_FLASH_LMA", flash0);
|
||||
|
||||
/* RAM region to be used for Main stack. This stack accommodates the processing
|
||||
of all exceptions and interrupts.*/
|
||||
REGION_ALIAS("MAIN_STACK_RAM", ram5);
|
||||
|
||||
/* RAM region to be used for the process stack. This is the stack used by
|
||||
the main() function.*/
|
||||
REGION_ALIAS("PROCESS_STACK_RAM", ram5);
|
||||
|
||||
/* RAM region to be used for data segment.*/
|
||||
REGION_ALIAS("DATA_RAM", ram1);
|
||||
REGION_ALIAS("DATA_RAM_LMA", flash0);
|
||||
|
||||
/* RAM region to be used for BSS segment.*/
|
||||
REGION_ALIAS("BSS_RAM", ram1);
|
||||
|
||||
/* RAM region to be used for the default heap.*/
|
||||
REGION_ALIAS("HEAP_RAM", ram1);
|
||||
|
||||
/* Stack rules inclusion.*/
|
||||
INCLUDE rules_stacks.ld
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Custom sections for STM32H7xx. */
|
||||
/* SRAM3 is assumed to be marked non-cacheable using MPU. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/* RAM region to be used for nocache segment.*/
|
||||
REGION_ALIAS("NOCACHE_RAM", ram0);
|
||||
|
||||
/* RAM region to be used for eth segment.*/
|
||||
REGION_ALIAS("ETH_RAM", ram3);
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/* Special section for non cache-able areas.*/
|
||||
.nocache (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
__nocache_base__ = .;
|
||||
*(.nocache)
|
||||
*(.nocache.*)
|
||||
*(.bss.__nocache_*)
|
||||
. = ALIGN(4);
|
||||
__nocache_end__ = .;
|
||||
} > NOCACHE_RAM
|
||||
|
||||
/* Special section for Ethernet DMA non cache-able areas.*/
|
||||
.eth (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
__eth_base__ = .;
|
||||
*(.eth)
|
||||
*(.eth.*)
|
||||
*(.bss.__eth_*)
|
||||
. = ALIGN(4);
|
||||
__eth_end__ = .;
|
||||
} > ETH_RAM
|
||||
}
|
||||
|
||||
/* Code rules inclusion.*/
|
||||
INCLUDE rules_code.ld
|
||||
|
||||
/* Data rules inclusion.*/
|
||||
INCLUDE rules_data.ld
|
||||
|
||||
/* Memory rules inclusion.*/
|
||||
INCLUDE rules_memory.ld
|
||||
|
||||
@@ -34,6 +34,21 @@
|
||||
/* Driver local variables and types. */
|
||||
/*===========================================================================*/
|
||||
|
||||
#if defined(STM32F1XX)
|
||||
|
||||
/**
|
||||
* @brief STM32 GPIO static initialization data.
|
||||
*/
|
||||
const PALConfig pal_default_config = {
|
||||
{VAL_GPIOA_ODR, VAL_GPIOA_CRL, VAL_GPIOA_CRH},
|
||||
{VAL_GPIOB_ODR, VAL_GPIOB_CRL, VAL_GPIOB_CRH},
|
||||
{VAL_GPIOC_ODR, VAL_GPIOC_CRL, VAL_GPIOC_CRH},
|
||||
{VAL_GPIOD_ODR, VAL_GPIOD_CRL, VAL_GPIOD_CRH},
|
||||
{VAL_GPIOE_ODR, VAL_GPIOE_CRL, VAL_GPIOE_CRH},
|
||||
};
|
||||
|
||||
#else /* STM32F1XX */
|
||||
|
||||
/**
|
||||
* @brief Type of STM32 GPIO port setup.
|
||||
*/
|
||||
@@ -91,48 +106,70 @@ typedef struct {
|
||||
*/
|
||||
static const gpio_config_t gpio_default_config = {
|
||||
#if STM32_HAS_GPIOA
|
||||
{VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
|
||||
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
|
||||
{
|
||||
VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
|
||||
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOB
|
||||
{VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
|
||||
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
|
||||
{
|
||||
VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
|
||||
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOC
|
||||
{VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
|
||||
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
|
||||
{
|
||||
VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
|
||||
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOD
|
||||
{VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
|
||||
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
|
||||
{
|
||||
VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
|
||||
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOE
|
||||
{VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
|
||||
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH},
|
||||
{
|
||||
VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
|
||||
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOF
|
||||
{VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
|
||||
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH},
|
||||
{
|
||||
VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
|
||||
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOG
|
||||
{VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
|
||||
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH},
|
||||
{
|
||||
VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
|
||||
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOH
|
||||
{VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
|
||||
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH},
|
||||
{
|
||||
VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
|
||||
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOI
|
||||
{VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
|
||||
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH},
|
||||
{
|
||||
VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
|
||||
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOJ
|
||||
{VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR,
|
||||
VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH},
|
||||
{
|
||||
VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR,
|
||||
VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH
|
||||
},
|
||||
#endif
|
||||
#if STM32_HAS_GPIOK
|
||||
{VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR,
|
||||
VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH}
|
||||
{
|
||||
VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR,
|
||||
VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
@@ -140,7 +177,8 @@ static const gpio_config_t gpio_default_config = {
|
||||
/* Driver local functions. */
|
||||
/*===========================================================================*/
|
||||
|
||||
static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) {
|
||||
static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config)
|
||||
{
|
||||
|
||||
gpiop->OTYPER = config->otyper;
|
||||
gpiop->OSPEEDR = config->ospeedr;
|
||||
@@ -151,12 +189,21 @@ static void gpio_init(stm32_gpio_t *gpiop, const gpio_setup_t *config) {
|
||||
gpiop->MODER = config->moder;
|
||||
}
|
||||
|
||||
static void stm32_gpio_init(void) {
|
||||
static void stm32_gpio_init(void)
|
||||
{
|
||||
|
||||
/* Enabling GPIO-related clocks, the mask comes from the
|
||||
registry header file.*/
|
||||
#if defined(STM32H7XX)
|
||||
rccResetAHB4(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB4(STM32_GPIO_EN_MASK, true);
|
||||
#elif defined(STM32F3XX)
|
||||
rccResetAHB(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB(STM32_GPIO_EN_MASK, true);
|
||||
#else
|
||||
rccResetAHB1(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB1(STM32_GPIO_EN_MASK, true);
|
||||
#endif
|
||||
|
||||
/* Initializing all the defined GPIO ports.*/
|
||||
#if STM32_HAS_GPIOA
|
||||
@@ -194,6 +241,8 @@ static void stm32_gpio_init(void) {
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* not STM32F1XX */
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Driver interrupt handlers. */
|
||||
/*===========================================================================*/
|
||||
@@ -207,8 +256,8 @@ static void stm32_gpio_init(void) {
|
||||
* @details GPIO ports and system clocks are initialized before everything
|
||||
* else.
|
||||
*/
|
||||
void __early_init(void) {
|
||||
|
||||
void __early_init(void)
|
||||
{
|
||||
stm32_gpio_init();
|
||||
stm32_clock_init();
|
||||
}
|
||||
@@ -217,18 +266,17 @@ void __early_init(void) {
|
||||
/**
|
||||
* @brief SDC card detection.
|
||||
*/
|
||||
bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
|
||||
bool sdc_lld_is_card_inserted(SDCDriver *sdcp)
|
||||
{
|
||||
(void)sdcp;
|
||||
/* assume card is inserted as there is no SD_DETECT pin
|
||||
* actual detection will be done by the software
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SDC card write protection detection.
|
||||
*/
|
||||
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
|
||||
bool sdc_lld_is_write_protected(SDCDriver *sdcp)
|
||||
{
|
||||
|
||||
(void)sdcp;
|
||||
return false;
|
||||
@@ -239,7 +287,8 @@ bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
|
||||
/**
|
||||
* @brief MMC_SPI card detection.
|
||||
*/
|
||||
bool mmc_lld_is_card_inserted(MMCDriver *mmcp) {
|
||||
bool mmc_lld_is_card_inserted(MMCDriver *mmcp)
|
||||
{
|
||||
|
||||
(void)mmcp;
|
||||
/* TODO: Fill the implementation.*/
|
||||
@@ -249,7 +298,8 @@ bool mmc_lld_is_card_inserted(MMCDriver *mmcp) {
|
||||
/**
|
||||
* @brief MMC_SPI card write protection detection.
|
||||
*/
|
||||
bool mmc_lld_is_write_protected(MMCDriver *mmcp) {
|
||||
bool mmc_lld_is_write_protected(MMCDriver *mmcp)
|
||||
{
|
||||
|
||||
(void)mmcp;
|
||||
/* TODO: Fill the implementation.*/
|
||||
@@ -261,17 +311,9 @@ bool mmc_lld_is_write_protected(MMCDriver *mmcp) {
|
||||
* @brief Board-specific initialization code.
|
||||
* @todo Add your board-specific code, if any.
|
||||
*/
|
||||
void boardInit(void) {
|
||||
|
||||
}
|
||||
|
||||
/** Energy saving procedure for SD log closing
|
||||
*/
|
||||
void mcu_periph_energy_save(void)
|
||||
void boardInit(void)
|
||||
{
|
||||
palSetLineMode(LINE_LED1, PAL_MODE_INPUT);
|
||||
palSetLineMode(LINE_OSD_CS, PAL_MODE_INPUT);
|
||||
palSetLineMode(LINE_IMU_CS, PAL_MODE_INPUT);
|
||||
palSetLineMode(LINE_SDCARD_CS, PAL_MODE_INPUT);
|
||||
#if defined(AFIO_MAPR_VAL)
|
||||
AFIO->MAPR |= AFIO_MAPR_VAL;
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
|
||||
ChibiOS - Copyright (C) 2006..2020 Giovanni Di Sirio
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
@@ -29,7 +29,27 @@
|
||||
#define CHCONF_H
|
||||
|
||||
#define _CHIBIOS_RT_CONF_
|
||||
#define _CHIBIOS_RT_CONF_VER_6_1_
|
||||
#define _CHIBIOS_RT_CONF_VER_7_0_
|
||||
|
||||
/*===========================================================================*/
|
||||
/**
|
||||
* @name System settings
|
||||
* @{
|
||||
*/
|
||||
/*===========================================================================*/
|
||||
|
||||
/**
|
||||
* @brief Handling of instances.
|
||||
* @note If enabled then threads assigned to various instances can
|
||||
* interact each other using the same synchronization objects.
|
||||
* If disabled then each OS instance is a separate world, no
|
||||
* direct interactions are handled by the OS.
|
||||
*/
|
||||
#if !defined(CH_CFG_SMP_MODE)
|
||||
#define CH_CFG_SMP_MODE FALSE
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
/*===========================================================================*/
|
||||
/**
|
||||
@@ -119,6 +139,19 @@
|
||||
#define CH_CFG_NO_IDLE_THREAD FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Kernel hardening level.
|
||||
* @details This option is the level of functional-safety checks enabled
|
||||
* in the kerkel. The meaning is:
|
||||
* - 0: No checks, maximum performance.
|
||||
* - 1: Reasonable checks.
|
||||
* - 2: All checks.
|
||||
* .
|
||||
*/
|
||||
#if !defined(CH_CFG_HARDENING_LEVEL)
|
||||
#define CH_CFG_HARDENING_LEVEL 0
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
/*===========================================================================*/
|
||||
@@ -160,6 +193,16 @@
|
||||
#define CH_CFG_USE_TM TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Time Stamps APIs.
|
||||
* @details If enabled then the time stamps APIs are included in the kernel.
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_TIMESTAMP)
|
||||
#define CH_CFG_USE_TIMESTAMP TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Threads registry APIs.
|
||||
* @details If enabled then the registry APIs are included in the kernel.
|
||||
@@ -330,6 +373,16 @@
|
||||
#define CH_CFG_USE_MAILBOXES TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Memory checks APIs.
|
||||
* @details If enabled then the memory checks APIs are included in the kernel.
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_MEMCHECKS)
|
||||
#define CH_CFG_USE_MEMCHECKS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Core Memory Manager APIs.
|
||||
* @details If enabled then the core memory manager APIs are included
|
||||
@@ -631,7 +684,7 @@
|
||||
* @details User fields added to the end of the @p ch_system_t structure.
|
||||
*/
|
||||
#define CH_CFG_SYSTEM_EXTRA_FIELDS \
|
||||
/* Add threads custom fields here.*/
|
||||
/* Add system custom fields here.*/
|
||||
|
||||
/**
|
||||
* @brief System initialization hook.
|
||||
@@ -639,7 +692,23 @@
|
||||
* just before interrupts are enabled globally.
|
||||
*/
|
||||
#define CH_CFG_SYSTEM_INIT_HOOK() { \
|
||||
/* Add threads initialization code here.*/ \
|
||||
/* Add system initialization code here.*/ \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief OS instance structure extension.
|
||||
* @details User fields added to the end of the @p os_instance_t structure.
|
||||
*/
|
||||
#define CH_CFG_OS_INSTANCE_EXTRA_FIELDS \
|
||||
/* Add OS instance custom fields here.*/
|
||||
|
||||
/**
|
||||
* @brief OS instance initialization hook.
|
||||
*
|
||||
* @param[in] oip pointer to the @p os_instance_t structure
|
||||
*/
|
||||
#define CH_CFG_OS_INSTANCE_INIT_HOOK(oip) { \
|
||||
/* Add OS instance initialization code here.*/ \
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -655,6 +724,8 @@
|
||||
*
|
||||
* @note It is invoked from within @p _thread_init() and implicitly from all
|
||||
* the threads creation APIs.
|
||||
*
|
||||
* @param[in] tp pointer to the @p thread_t structure
|
||||
*/
|
||||
#define CH_CFG_THREAD_INIT_HOOK(tp) { \
|
||||
/* Add threads initialization code here.*/ \
|
||||
@@ -663,6 +734,8 @@
|
||||
/**
|
||||
* @brief Threads finalization hook.
|
||||
* @details User finalization code added to the @p chThdExit() API.
|
||||
*
|
||||
* @param[in] tp pointer to the @p thread_t structure
|
||||
*/
|
||||
#define CH_CFG_THREAD_EXIT_HOOK(tp) { \
|
||||
/* Add threads finalization code here.*/ \
|
||||
@@ -671,6 +744,9 @@
|
||||
/**
|
||||
* @brief Context switch hook.
|
||||
* @details This hook is invoked just before switching between threads.
|
||||
*
|
||||
* @param[in] ntp thread being switched in
|
||||
* @param[in] otp thread being switched out
|
||||
*/
|
||||
#define CH_CFG_CONTEXT_SWITCH_HOOK(ntp, otp) { \
|
||||
/* Context switch code here.*/ \
|
||||
@@ -745,31 +821,20 @@
|
||||
/* Trace code here.*/ \
|
||||
}
|
||||
|
||||
/** @} */
|
||||
/**
|
||||
* @brief Runtime Faults Collection Unit hook.
|
||||
* @details This hook is invoked each time new faults are collected and stored.
|
||||
*/
|
||||
#define CH_CFG_RUNTIME_FAULTS_HOOK(mask) { \
|
||||
/* Faults handling code here.*/ \
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Port-specific settings (override port settings defaulted in chcore.h). */
|
||||
/*===========================================================================*/
|
||||
|
||||
|
||||
|
||||
#ifndef CORTEX_VTOR_INIT // try to find the correct init address if not defined
|
||||
|
||||
#if LUFTBOOT // using LUFTBOOT bootloader
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define CORTEX_VTOR_INIT 0x00004000U
|
||||
#elif defined(STM32F7)
|
||||
#define CORTEX_VTOR_INIT 0x08008000U
|
||||
#else
|
||||
#define CORTEX_VTOR_INIT 0x00002000U
|
||||
#endif
|
||||
|
||||
#endif // LUFTBOOT
|
||||
|
||||
#endif // CORTEX_VTOR_INIT
|
||||
|
||||
// allow float for the ChibiOS print function (used with logger)
|
||||
#define CHPRINTF_USE_FLOAT 1
|
||||
|
||||
|
||||
+98
-162
@@ -1,21 +1,41 @@
|
||||
#ifndef CONFIG_PX4FMU_5_00_H
|
||||
#define CONFIG_PX4FMU_5_00_H
|
||||
|
||||
#define BOARD_PX4FMU
|
||||
/*
|
||||
* Copyright (C) 2022 Freek van Tienen <freek.v.tienen@gmail.com>
|
||||
*
|
||||
* This file is part of Paparazzi.
|
||||
*
|
||||
* Paparazzi is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Paparazzi is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Paparazzi; see the file COPYING. If not, write to
|
||||
* the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
* Boston, MA 02111-1307, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* ChibiOS board file
|
||||
* @file arch/chibios/common_board.h
|
||||
* @brief Generic board file
|
||||
*/
|
||||
#include "boards/px4fmu/chibios/v5.0/board.h"
|
||||
|
||||
#ifndef ARCH_COMMON_BOARD_H
|
||||
#define ARCH_COMMON_BOARD_H
|
||||
/**
|
||||
* PPRZ definitions
|
||||
* ChibiOS board file generated by the cfg file
|
||||
*/
|
||||
#include "board.h"
|
||||
|
||||
/*
|
||||
* AHB_CLK
|
||||
* Concat macro
|
||||
*/
|
||||
#define AHB_CLK STM32_HCLK
|
||||
#define _CONCAT_BOARD_PARAM(_s1, _s2) _s1 ## _s2
|
||||
#define CONCAT_BOARD_PARAM(_s1, _s2) _CONCAT_BOARD_PARAM(_s1, _s2)
|
||||
|
||||
/*
|
||||
* LEDs
|
||||
@@ -28,7 +48,6 @@
|
||||
#define LED_1_GPIO_PIN PAL_PAD(LINE_LED1)
|
||||
#define LED_1_GPIO_ON gpio_clear
|
||||
#define LED_1_GPIO_OFF gpio_set
|
||||
#define LED_1_AFIO_REMAP ((void)0)
|
||||
#endif
|
||||
|
||||
#if defined(LINE_LED2)
|
||||
@@ -39,7 +58,6 @@
|
||||
#define LED_2_GPIO_PIN PAL_PAD(LINE_LED2)
|
||||
#define LED_2_GPIO_ON gpio_clear
|
||||
#define LED_2_GPIO_OFF gpio_set
|
||||
#define LED_2_AFIO_REMAP ((void)0)
|
||||
#endif
|
||||
|
||||
#if defined(LINE_LED3)
|
||||
@@ -50,7 +68,6 @@
|
||||
#define LED_3_GPIO_PIN PAL_PAD(LINE_LED3)
|
||||
#define LED_3_GPIO_ON gpio_clear
|
||||
#define LED_3_GPIO_OFF gpio_set
|
||||
#define LED_3_AFIO_REMAP ((void)0)
|
||||
#endif
|
||||
|
||||
#if defined(LINE_LED4)
|
||||
@@ -61,7 +78,6 @@
|
||||
#define LED_4_GPIO_PIN PAL_PAD(LINE_LED4)
|
||||
#define LED_4_GPIO_ON gpio_clear
|
||||
#define LED_4_GPIO_OFF gpio_set
|
||||
#define LED_4_AFIO_REMAP ((void)0)
|
||||
#endif
|
||||
|
||||
/*
|
||||
@@ -72,7 +88,11 @@
|
||||
#define USE_ADC_1 1
|
||||
#endif
|
||||
#if USE_ADC_1
|
||||
#define AD1_1_CHANNEL ADC_CHANNEL_IN0
|
||||
#if defined(ADC1_ADC_IN)
|
||||
#define AD1_1_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC1_ADC_IN)
|
||||
#elif defined(ADC1_ADC_INP)
|
||||
#define AD1_1_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC1_ADC_INP)
|
||||
#endif
|
||||
#define ADC_1 AD1_1
|
||||
#define ADC_1_GPIO_PORT PAL_PORT(LINE_ADC1)
|
||||
#define ADC_1_GPIO_PIN PAL_PAD(LINE_ADC1)
|
||||
@@ -84,7 +104,11 @@
|
||||
#define USE_ADC_2 1
|
||||
#endif
|
||||
#if USE_ADC_2
|
||||
#define AD1_2_CHANNEL ADC_CHANNEL_IN1
|
||||
#if defined(ADC2_ADC_IN)
|
||||
#define AD1_2_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC2_ADC_IN)
|
||||
#elif defined(ADC2_ADC_INP)
|
||||
#define AD1_2_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC2_ADC_INP)
|
||||
#endif
|
||||
#define ADC_2 AD1_2
|
||||
#define ADC_2_GPIO_PORT PAL_PORT(LINE_ADC2)
|
||||
#define ADC_2_GPIO_PIN PAL_PAD(LINE_ADC2)
|
||||
@@ -96,7 +120,11 @@
|
||||
#define USE_ADC_3 1
|
||||
#endif
|
||||
#if USE_ADC_3
|
||||
#define AD1_3_CHANNEL ADC_CHANNEL_IN2
|
||||
#if defined(ADC3_ADC_IN)
|
||||
#define AD1_3_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC3_ADC_IN)
|
||||
#elif defined(ADC3_ADC_INP)
|
||||
#define AD1_3_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC3_ADC_INP)
|
||||
#endif
|
||||
#define ADC_3 AD1_3
|
||||
#define ADC_3_GPIO_PORT PAL_PORT(LINE_ADC3)
|
||||
#define ADC_3_GPIO_PIN PAL_PAD(LINE_ADC3)
|
||||
@@ -108,7 +136,11 @@
|
||||
#define USE_ADC_4 1
|
||||
#endif
|
||||
#if USE_ADC_4
|
||||
#define AD1_4_CHANNEL ADC_CHANNEL_IN3
|
||||
#if defined(ADC4_ADC_IN)
|
||||
#define AD1_4_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC4_ADC_IN)
|
||||
#elif defined(ADC4_ADC_INP)
|
||||
#define AD1_4_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC4_ADC_INP)
|
||||
#endif
|
||||
#define ADC_4 AD1_4
|
||||
#define ADC_4_GPIO_PORT PAL_PORT(LINE_ADC4)
|
||||
#define ADC_4_GPIO_PIN PAL_PAD(LINE_ADC4)
|
||||
@@ -116,8 +148,15 @@
|
||||
#endif
|
||||
|
||||
#if defined(LINE_ADC5)
|
||||
#ifndef USE_ADC_5
|
||||
#define USE_ADC_5 1
|
||||
#endif
|
||||
#if USE_ADC_5
|
||||
#define AD1_5_CHANNEL ADC_CHANNEL_IN4
|
||||
#if defined(ADC5_ADC_IN)
|
||||
#define AD1_5_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC5_ADC_IN)
|
||||
#elif defined(ADC5_ADC_INP)
|
||||
#define AD1_5_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC5_ADC_INP)
|
||||
#endif
|
||||
#define ADC_5 AD1_5
|
||||
#define ADC_5_GPIO_PORT PAL_PORT(LINE_ADC5)
|
||||
#define ADC_5_GPIO_PIN PAL_PAD(LINE_ADC5)
|
||||
@@ -126,29 +165,19 @@
|
||||
|
||||
#if defined(LINE_ADC6)
|
||||
#if USE_ADC_6
|
||||
#define AD1_6_CHANNEL ADC_CHANNEL_IN14
|
||||
#if defined(ADC6_ADC_IN)
|
||||
#define AD1_6_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC6_ADC_IN)
|
||||
#elif defined(ADC6_ADC_INP)
|
||||
#define AD1_6_CHANNEL CONCAT_BOARD_PARAM(ADC_CHANNEL_IN, ADC6_ADC_INP)
|
||||
#endif
|
||||
#define ADC_6 AD1_6
|
||||
#define ADC_6_GPIO_PORT PAL_PORT(LINE_ADC6)
|
||||
#define ADC_6_GPIO_PIN PAL_PAD(LINE_ADC6)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
|
||||
#ifndef ADC_CHANNEL_VSUPPLY
|
||||
#define ADC_CHANNEL_VSUPPLY ADC_1
|
||||
#endif
|
||||
|
||||
/* allow to define ADC_CHANNEL_CURRENT in the airframe file*/
|
||||
#if !defined(ADC_CHANNEL_CURRENT) && !ADC_CURRENT_DISABLE
|
||||
#define ADC_CHANNEL_CURRENT ADC_2
|
||||
#endif
|
||||
|
||||
/* Default powerbrick values */
|
||||
#define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 10.3208191126f * adc)
|
||||
#define MilliAmpereOfAdc(adc) ((3.3f/4096.0f) * 24000.0f * adc)
|
||||
|
||||
/*
|
||||
* PWM defines (TODO DRIVER and CHANNEL)
|
||||
* PWM defines
|
||||
*/
|
||||
#if defined(LINE_SERVO1)
|
||||
#ifndef USE_PWM1
|
||||
@@ -159,11 +188,9 @@
|
||||
#define PWM_SERVO_1_GPIO PAL_PORT(LINE_SERVO1)
|
||||
#define PWM_SERVO_1_PIN PAL_PAD(LINE_SERVO1)
|
||||
#define PWM_SERVO_1_AF AF_LINE_SERVO1
|
||||
#define PWM_SERVO_1_DRIVER PWMD1
|
||||
#define PWM_SERVO_1_CHANNEL 4-1
|
||||
#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_1_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_1_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO1_TIM)
|
||||
#define PWM_SERVO_1_CHANNEL (SERVO1_TIM_CH-1)
|
||||
#define PWM_SERVO_1_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO1_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -176,11 +203,9 @@
|
||||
#define PWM_SERVO_2_GPIO PAL_PORT(LINE_SERVO2)
|
||||
#define PWM_SERVO_2_PIN PAL_PAD(LINE_SERVO2)
|
||||
#define PWM_SERVO_2_AF AF_LINE_SERVO2
|
||||
#define PWM_SERVO_2_DRIVER PWMD1
|
||||
#define PWM_SERVO_2_CHANNEL 3-1
|
||||
#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_2_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_2_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO2_TIM)
|
||||
#define PWM_SERVO_2_CHANNEL (SERVO2_TIM_CH-1)
|
||||
#define PWM_SERVO_2_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO2_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -193,11 +218,9 @@
|
||||
#define PWM_SERVO_3_GPIO PAL_PORT(LINE_SERVO3)
|
||||
#define PWM_SERVO_3_PIN PAL_PAD(LINE_SERVO3)
|
||||
#define PWM_SERVO_3_AF AF_LINE_SERVO3
|
||||
#define PWM_SERVO_3_DRIVER PWMD1
|
||||
#define PWM_SERVO_3_CHANNEL 2-1
|
||||
#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_3_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_3_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO3_TIM)
|
||||
#define PWM_SERVO_3_CHANNEL (SERVO3_TIM_CH-1)
|
||||
#define PWM_SERVO_3_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO3_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -210,11 +233,9 @@
|
||||
#define PWM_SERVO_4_GPIO PAL_PORT(LINE_SERVO4)
|
||||
#define PWM_SERVO_4_PIN PAL_PAD(LINE_SERVO4)
|
||||
#define PWM_SERVO_4_AF AF_LINE_SERVO4
|
||||
#define PWM_SERVO_4_DRIVER PWMD1
|
||||
#define PWM_SERVO_4_CHANNEL 1-1
|
||||
#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_4_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_4_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO4_TIM)
|
||||
#define PWM_SERVO_4_CHANNEL (SERVO4_TIM_CH-1)
|
||||
#define PWM_SERVO_4_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO4_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -227,11 +248,9 @@
|
||||
#define PWM_SERVO_5_GPIO PAL_PORT(LINE_SERVO5)
|
||||
#define PWM_SERVO_5_PIN PAL_PAD(LINE_SERVO5)
|
||||
#define PWM_SERVO_5_AF AF_LINE_SERVO5
|
||||
#define PWM_SERVO_5_DRIVER PWMD4
|
||||
#define PWM_SERVO_5_CHANNEL 2-1
|
||||
#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_5_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_5_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO5_TIM)
|
||||
#define PWM_SERVO_5_CHANNEL (SERVO5_TIM_CH-1)
|
||||
#define PWM_SERVO_5_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO5_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -244,11 +263,9 @@
|
||||
#define PWM_SERVO_6_GPIO PAL_PORT(LINE_SERVO6)
|
||||
#define PWM_SERVO_6_PIN PAL_PAD(LINE_SERVO6)
|
||||
#define PWM_SERVO_6_AF AF_LINE_SERVO6
|
||||
#define PWM_SERVO_6_DRIVER PWMD4
|
||||
#define PWM_SERVO_6_CHANNEL 3-1
|
||||
#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_6_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_6_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO6_TIM)
|
||||
#define PWM_SERVO_6_CHANNEL (SERVO6_TIM_CH-1)
|
||||
#define PWM_SERVO_6_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO6_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -261,11 +278,9 @@
|
||||
#define PWM_SERVO_7_GPIO PAL_PORT(LINE_SERVO7)
|
||||
#define PWM_SERVO_7_PIN PAL_PAD(LINE_SERVO7)
|
||||
#define PWM_SERVO_7_AF AF_LINE_SERVO7
|
||||
#define PWM_SERVO_7_DRIVER PWMD12
|
||||
#define PWM_SERVO_7_CHANNEL 1-1
|
||||
#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_7_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_7_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO7_TIM)
|
||||
#define PWM_SERVO_7_CHANNEL (SERVO7_TIM_CH-1)
|
||||
#define PWM_SERVO_7_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO7_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -278,80 +293,12 @@
|
||||
#define PWM_SERVO_8_GPIO PAL_PORT(LINE_SERVO8)
|
||||
#define PWM_SERVO_8_PIN PAL_PAD(LINE_SERVO8)
|
||||
#define PWM_SERVO_8_AF AF_LINE_SERVO8
|
||||
#define PWM_SERVO_8_DRIVER PWMD12
|
||||
#define PWM_SERVO_8_CHANNEL 2-1
|
||||
#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_ACTIVE_HIGH
|
||||
#else
|
||||
#define PWM_SERVO_8_ACTIVE PWM_OUTPUT_DISABLED
|
||||
#define PWM_SERVO_8_DRIVER CONCAT_BOARD_PARAM(PWMD, SERVO8_TIM)
|
||||
#define PWM_SERVO_8_CHANNEL (SERVO8_TIM_CH-1)
|
||||
#define PWM_SERVO_8_CONF CONCAT_BOARD_PARAM(pwmcfg, SERVO8_TIM)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef STM32_PWM_USE_TIM1
|
||||
#define PWM_CONF_TIM1 STM32_PWM_USE_TIM1
|
||||
#else
|
||||
#define PWM_CONF_TIM1 1
|
||||
#endif
|
||||
#define PWM_CONF1_DEF { \
|
||||
PWM_FREQUENCY, \
|
||||
PWM_FREQUENCY/TIM1_SERVO_HZ, \
|
||||
NULL, \
|
||||
{ \
|
||||
{ PWM_SERVO_4_ACTIVE, NULL }, \
|
||||
{ PWM_SERVO_3_ACTIVE, NULL }, \
|
||||
{ PWM_SERVO_2_ACTIVE, NULL }, \
|
||||
{ PWM_SERVO_1_ACTIVE, NULL }, \
|
||||
}, \
|
||||
0, \
|
||||
0 \
|
||||
}
|
||||
|
||||
#ifdef STM32_PWM_USE_TIM4
|
||||
#define PWM_CONF_TIM4 STM32_PWM_USE_TIM4
|
||||
#else
|
||||
#define PWM_CONF_TIM4 1
|
||||
#endif
|
||||
#define PWM_CONF4_DEF { \
|
||||
PWM_FREQUENCY, \
|
||||
PWM_FREQUENCY/TIM4_SERVO_HZ, \
|
||||
NULL, \
|
||||
{ \
|
||||
{ PWM_OUTPUT_DISABLED, NULL }, \
|
||||
{ PWM_SERVO_5_ACTIVE, NULL }, \
|
||||
{ PWM_SERVO_6_ACTIVE, NULL }, \
|
||||
{ PWM_OUTPUT_DISABLED, NULL }, \
|
||||
}, \
|
||||
0, \
|
||||
0 \
|
||||
}
|
||||
|
||||
#ifdef STM32_PWM_USE_TIM12
|
||||
#define PWM_CONF_TIM12 STM32_PWM_USE_TIM12
|
||||
#else
|
||||
#define PWM_CONF_TIM12 1
|
||||
#endif
|
||||
#define PWM_CONF12_DEF { \
|
||||
PWM_FREQUENCY, \
|
||||
PWM_FREQUENCY/TIM12_SERVO_HZ, \
|
||||
NULL, \
|
||||
{ \
|
||||
{ PWM_SERVO_7_ACTIVE, NULL }, \
|
||||
{ PWM_SERVO_8_ACTIVE, NULL }, \
|
||||
{ PWM_OUTPUT_DISABLED, NULL }, \
|
||||
{ PWM_OUTPUT_DISABLED, NULL }, \
|
||||
}, \
|
||||
0, \
|
||||
0 \
|
||||
}
|
||||
|
||||
/**
|
||||
* PPM radio defines
|
||||
*/
|
||||
#define RC_PPM_TICKS_PER_USEC 2
|
||||
#define PPM_TIMER_FREQUENCY 2000000
|
||||
#define PPM_CHANNEL ICU_CHANNEL_1
|
||||
#define PPM_TIMER ICUD8
|
||||
|
||||
/**
|
||||
* UART defines
|
||||
*/
|
||||
@@ -483,9 +430,6 @@
|
||||
#define UART8_GPIO_AF ((void)0)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* I2C defines
|
||||
*/
|
||||
/**
|
||||
* I2C defines
|
||||
*/
|
||||
@@ -700,14 +644,14 @@
|
||||
#define SPI_SELECT_SLAVE6_PIN PAL_PAD(LINE_SPI_SLAVE6)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Baro
|
||||
*
|
||||
* Apparently needed for backwards compatibility
|
||||
* with the ancient onboard baro boards
|
||||
*/
|
||||
#ifndef USE_BARO_BOARD
|
||||
#define USE_BARO_BOARD 1
|
||||
#if defined(LINE_SPI_SLAVE7)
|
||||
#define SPI_SELECT_SLAVE7_PORT PAL_PORT(LINE_SPI_SLAVE7)
|
||||
#define SPI_SELECT_SLAVE7_PIN PAL_PAD(LINE_SPI_SLAVE7)
|
||||
#endif
|
||||
|
||||
#if defined(LINE_SPI_SLAVE8)
|
||||
#define SPI_SELECT_SLAVE8_PORT PAL_PORT(LINE_SPI_SLAVE8)
|
||||
#define SPI_SELECT_SLAVE8_PIN PAL_PAD(LINE_SPI_SLAVE8)
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -737,16 +681,9 @@
|
||||
#if defined(LINE_USB_VBUS)
|
||||
#define SDLOG_USB_VBUS_PORT PAL_PORT(LINE_USB_VBUS)
|
||||
#define SDLOG_USB_VBUS_PIN PAL_PAD(LINE_USB_VBUS)
|
||||
#define SDLOG_USB_VBUS_BOOT true
|
||||
#define SDLOG_USB_VBUS_BOOT false
|
||||
#endif
|
||||
|
||||
// bat monitoring for file closing
|
||||
#define SDLOG_BAT_ADC ADCD1
|
||||
#define SDLOG_BAT_CHAN AD1_1_CHANNEL
|
||||
// usb led status
|
||||
#define SDLOG_USB_LED 3
|
||||
|
||||
|
||||
/*
|
||||
* Actuators for fixedwing
|
||||
*/
|
||||
@@ -756,5 +693,4 @@
|
||||
#define ActuatorsDefaultInit() ActuatorsPwmInit()
|
||||
#define ActuatorsDefaultCommit() ActuatorsPwmCommit()
|
||||
|
||||
#endif /* CONFIG_PX4FMU_4_00_H */
|
||||
|
||||
#endif /* ARCH_COMMON_BOARD_H */
|
||||
@@ -1,11 +1,12 @@
|
||||
/* CHIBIOS FIX */
|
||||
#include "ch.h"
|
||||
#define FATFS_CHIBIOS_EXTENSIONS
|
||||
|
||||
/*---------------------------------------------------------------------------/
|
||||
/ FatFs - FAT file system module configuration file
|
||||
/ FatFs Functional Configurations
|
||||
/---------------------------------------------------------------------------*/
|
||||
|
||||
#define FFCONF_DEF 86606 /* Revision ID */
|
||||
#define FFCONF_DEF 86631 /* Revision ID */
|
||||
|
||||
/*---------------------------------------------------------------------------/
|
||||
/ Function Configurations
|
||||
@@ -28,55 +29,69 @@
|
||||
/ 3: f_lseek() function is removed in addition to 2. */
|
||||
|
||||
|
||||
#define FF_USE_STRFUNC 0
|
||||
/* This option switches string functions, f_gets(), f_putc(), f_puts() and
|
||||
/ f_printf().
|
||||
/
|
||||
/ 0: Disable string functions.
|
||||
/ 1: Enable without LF-CRLF conversion.
|
||||
/ 2: Enable with LF-CRLF conversion. */
|
||||
|
||||
|
||||
#define FF_USE_FIND 1
|
||||
#define FF_USE_FIND 1
|
||||
/* This option switches filtered directory read functions, f_findfirst() and
|
||||
/ f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */
|
||||
|
||||
|
||||
#define FF_USE_MKFS 1
|
||||
#define FF_USE_MKFS 1
|
||||
/* This option switches f_mkfs() function. (0:Disable or 1:Enable) */
|
||||
|
||||
|
||||
#define FF_USE_FASTSEEK 1
|
||||
#define FF_USE_FASTSEEK 1
|
||||
/* This option switches fast seek function. (0:Disable or 1:Enable) */
|
||||
|
||||
|
||||
#define FF_USE_EXPAND 1
|
||||
#define FF_USE_EXPAND 1
|
||||
/* This option switches f_expand function. (0:Disable or 1:Enable) */
|
||||
|
||||
|
||||
#define FF_USE_CHMOD 1
|
||||
#define FF_USE_CHMOD 1
|
||||
/* This option switches attribute manipulation functions, f_chmod() and f_utime().
|
||||
/ (0:Disable or 1:Enable) Also FF_FS_READONLY needs to be 0 to enable this option. */
|
||||
|
||||
|
||||
#define FF_USE_LABEL 1
|
||||
#define FF_USE_LABEL 1
|
||||
/* This option switches volume label functions, f_getlabel() and f_setlabel().
|
||||
/ (0:Disable or 1:Enable) */
|
||||
|
||||
|
||||
#define FF_USE_FORWARD 1
|
||||
#define FF_USE_FORWARD 1
|
||||
/* This option switches f_forward() function. (0:Disable or 1:Enable) */
|
||||
|
||||
|
||||
#define FF_USE_STRFUNC 0
|
||||
#define FF_PRINT_LLI 0
|
||||
#define FF_PRINT_FLOAT 0
|
||||
#define FF_STRF_ENCODE 0
|
||||
/* FF_USE_STRFUNC switches string functions, f_gets(), f_putc(), f_puts() and
|
||||
/ f_printf().
|
||||
/
|
||||
/ 0: Disable. FF_PRINT_LLI, FF_PRINT_FLOAT and FF_STRF_ENCODE have no effect.
|
||||
/ 1: Enable without LF-CRLF conversion.
|
||||
/ 2: Enable with LF-CRLF conversion.
|
||||
/
|
||||
/ FF_PRINT_LLI = 1 makes f_printf() support long long argument and FF_PRINT_FLOAT = 1/2
|
||||
makes f_printf() support floating point argument. These features want C99 or later.
|
||||
/ When FF_LFN_UNICODE >= 1 with LFN enabled, string functions convert the character
|
||||
/ encoding in it. FF_STRF_ENCODE selects assumption of character encoding ON THE FILE
|
||||
/ to be read/written via those functions.
|
||||
/
|
||||
/ 0: ANSI/OEM in current CP
|
||||
/ 1: Unicode in UTF-16LE
|
||||
/ 2: Unicode in UTF-16BE
|
||||
/ 3: Unicode in UTF-8
|
||||
*/
|
||||
|
||||
|
||||
/*---------------------------------------------------------------------------/
|
||||
/ Locale and Namespace Configurations
|
||||
/---------------------------------------------------------------------------*/
|
||||
|
||||
#define FF_CODE_PAGE 850
|
||||
#define FF_CODE_PAGE 850
|
||||
/* This option specifies the OEM code page to be used on the target system.
|
||||
/ Incorrect setting of the code page can cause a file open failure.
|
||||
/ Incorrect code page setting can cause a file open failure.
|
||||
/
|
||||
/ 1 - ASCII (No extended character. Non-LFN cfg. only)
|
||||
/ 437 - U.S.
|
||||
/ 720 - Arabic
|
||||
/ 737 - Greek
|
||||
@@ -98,31 +113,40 @@
|
||||
/ 936 - Simplified Chinese (DBCS)
|
||||
/ 949 - Korean (DBCS)
|
||||
/ 950 - Traditional Chinese (DBCS)
|
||||
/ 0 - Include all code pages above and configured by f_setcp()
|
||||
*/
|
||||
|
||||
|
||||
#define FF_USE_LFN 2
|
||||
#define FF_MAX_LFN 255
|
||||
/* The FF_USE_LFN switches the support of long file name (LFN).
|
||||
#define FF_USE_LFN 2
|
||||
#define FF_MAX_LFN 255
|
||||
/* The FF_USE_LFN switches the support for LFN (long file name).
|
||||
/
|
||||
/ 0: Disable support of LFN. _MAX_LFN has no effect.
|
||||
/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
|
||||
/ 0: Disable LFN. FF_MAX_LFN has no effect.
|
||||
/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
|
||||
/ 2: Enable LFN with dynamic working buffer on the STACK.
|
||||
/ 3: Enable LFN with dynamic working buffer on the HEAP.
|
||||
/
|
||||
/ To enable the LFN, Unicode handling functions (option/unicode.c) must be added
|
||||
/ to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and
|
||||
/ additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255.
|
||||
/ It should be set 255 to support full featured LFN operations.
|
||||
/ To enable the LFN, ffunicode.c needs to be added to the project. The LFN function
|
||||
/ requiers certain internal working buffer occupies (FF_MAX_LFN + 1) * 2 bytes and
|
||||
/ additional (FF_MAX_LFN + 44) / 15 * 32 bytes when exFAT is enabled.
|
||||
/ The FF_MAX_LFN defines size of the working buffer in UTF-16 code unit and it can
|
||||
/ be in range of 12 to 255. It is recommended to be set it 255 to fully support LFN
|
||||
/ specification.
|
||||
/ When use stack for the working buffer, take care on stack overflow. When use heap
|
||||
/ memory for the working buffer, memory management functions, ff_memalloc() and
|
||||
/ ff_memfree(), must be added to the project. */
|
||||
/ ff_memfree() exemplified in ffsystem.c, need to be added to the project. */
|
||||
|
||||
|
||||
#define FF_LFN_UNICODE 0
|
||||
/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16)
|
||||
/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1.
|
||||
/ This option also affects behavior of string I/O functions. */
|
||||
#define FF_LFN_UNICODE 0
|
||||
/* This option switches the character encoding on the API when LFN is enabled.
|
||||
/
|
||||
/ 0: ANSI/OEM in current CP (TCHAR = char)
|
||||
/ 1: Unicode in UTF-16 (TCHAR = WCHAR)
|
||||
/ 2: Unicode in UTF-8 (TCHAR = char)
|
||||
/ 3: Unicode in UTF-32 (TCHAR = DWORD)
|
||||
/
|
||||
/ Also behavior of string I/O functions will be affected by this option.
|
||||
/ When LFN is not enabled, this option has no effect. */
|
||||
|
||||
|
||||
#define FF_LFN_BUF 255
|
||||
@@ -133,22 +157,8 @@
|
||||
/ on character encoding. When LFN is not enabled, these options have no effect. */
|
||||
|
||||
|
||||
#define FF_STRF_ENCODE 3
|
||||
/* When FF_LFN_UNICODE >= 1 with LFN enabled, string I/O functions, f_gets(),
|
||||
/ f_putc(), f_puts and f_printf() convert the character encoding in it.
|
||||
/ This option selects assumption of character encoding ON THE FILE to be
|
||||
/ read/written via those functions.
|
||||
/
|
||||
/ 0: ANSI/OEM
|
||||
/ 1: UTF-16LE
|
||||
/ 2: UTF-16BE
|
||||
/ 3: UTF-8
|
||||
/
|
||||
/ This option has no effect when _LFN_UNICODE == 0. */
|
||||
|
||||
|
||||
#define FF_FS_RPATH 1
|
||||
/* This option configures support of relative path.
|
||||
#define FF_FS_RPATH 1
|
||||
/* This option configures support for relative path.
|
||||
/
|
||||
/ 0: Disable relative path and remove related functions.
|
||||
/ 1: Enable relative path. f_chdir() and f_chdrive() are available.
|
||||
@@ -160,8 +170,8 @@
|
||||
/ Drive/Volume Configurations
|
||||
/---------------------------------------------------------------------------*/
|
||||
|
||||
#define FF_VOLUMES 1
|
||||
/* Number of volumes (logical drives) to be used. */
|
||||
#define FF_VOLUMES 1
|
||||
/* Number of volumes (logical drives) to be used. (1-10) */
|
||||
|
||||
|
||||
#define FF_STR_VOLUME_ID 0
|
||||
@@ -191,7 +201,7 @@
|
||||
#define FF_MAX_SS 512
|
||||
/* This set of options configures the range of sector size to be supported. (512,
|
||||
/ 1024, 2048 or 4096) Always set both 512 for most systems, generic memory card and
|
||||
/ harddisk. But a larger value may be required for on-board flash memory and some
|
||||
/ harddisk, but a larger value may be required for on-board flash memory and some
|
||||
/ type of optical media. When FF_MAX_SS is larger than FF_MIN_SS, FatFs is configured
|
||||
/ for variable sector size mode and disk_ioctl() function needs to implement
|
||||
/ GET_SECTOR_SIZE command. */
|
||||
@@ -203,7 +213,7 @@
|
||||
|
||||
|
||||
#define FF_MIN_GPT 0x100000000
|
||||
/* Minimum number of sectors to switch GPT format to create partition in f_mkfs and
|
||||
/* Minimum number of sectors to switch GPT as partitioning format in f_mkfs and
|
||||
/ f_fdisk function. 0x100000000 max. This option has no effect when FF_LBA64 == 0. */
|
||||
|
||||
|
||||
@@ -234,7 +244,7 @@
|
||||
#define FF_FS_NORTC 0
|
||||
#define FF_NORTC_MON 1
|
||||
#define FF_NORTC_MDAY 1
|
||||
#define FF_NORTC_YEAR 2019
|
||||
#define FF_NORTC_YEAR 2020
|
||||
/* The option FF_FS_NORTC switches timestamp functiton. If the system does not have
|
||||
/ any RTC function or valid timestamp is not needed, set FF_FS_NORTC = 1 to disable
|
||||
/ the timestamp function. Every object modified by FatFs will have a fixed timestamp
|
||||
@@ -278,18 +288,17 @@
|
||||
/ and f_fdisk() function, are always not re-entrant. Only file/directory access
|
||||
/ to the same volume is under control of this function.
|
||||
/
|
||||
/ 0: Disable re-entrancy. FF_FS_TIMEOUT and _SYNC_t have no effect.
|
||||
/ 0: Disable re-entrancy. FF_FS_TIMEOUT and FF_SYNC_t have no effect.
|
||||
/ 1: Enable re-entrancy. Also user provided synchronization handlers,
|
||||
/ ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj()
|
||||
/ function, must be added to the project. Samples are available in
|
||||
/ option/syscall.c.
|
||||
/
|
||||
/ The FF_FS_TIMEOUT defines timeout period in unit of time tick.
|
||||
/ The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
|
||||
/ SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be
|
||||
/ The FF_SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
|
||||
/ SemaphoreHandle_t and etc. A header file for O/S definitions needs to be
|
||||
/ included somewhere in the scope of ff.h. */
|
||||
|
||||
/* #include <windows.h> // O/S definitions */
|
||||
|
||||
|
||||
/*--- End of configuration options ---*/
|
||||
|
||||
@@ -1,13 +1,5 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
|
||||
|
||||
modified by: AggieAir, A Remote Sensing Unmanned Aerial System for Scientific Applications
|
||||
Utah State University, http://aggieair.usu.edu/
|
||||
|
||||
Michal Podhradsky (michal.podhradsky@aggiemail.usu.edu)
|
||||
Calvin Coopmans (c.r.coopmans@ieee.org)
|
||||
|
||||
modified by Gautier Hattenberger for STM32F7 support
|
||||
ChibiOS - Copyright (C) 2006..2020 Giovanni Di Sirio
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
@@ -37,7 +29,7 @@
|
||||
#define HALCONF_H
|
||||
|
||||
#define _CHIBIOS_HAL_CONF_
|
||||
#define _CHIBIOS_HAL_CONF_VER_7_1_
|
||||
#define _CHIBIOS_HAL_CONF_VER_8_0_
|
||||
|
||||
#include "mcuconf.h"
|
||||
|
||||
@@ -45,7 +37,7 @@
|
||||
* @brief Enables the PAL subsystem.
|
||||
*/
|
||||
#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__)
|
||||
#define HAL_USE_PAL TRUE
|
||||
#define HAL_USE_PAL TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -53,9 +45,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__)
|
||||
#if USE_ADC
|
||||
#define HAL_USE_ADC TRUE
|
||||
#define HAL_USE_ADC TRUE
|
||||
#else
|
||||
#define HAL_USE_ADC FALSE
|
||||
#define HAL_USE_ADC FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -64,9 +56,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__)
|
||||
#if USE_CAN1 || USE_CAN2
|
||||
#define HAL_USE_CAN TRUE
|
||||
#define HAL_USE_CAN TRUE
|
||||
#else
|
||||
#define HAL_USE_CAN FALSE
|
||||
#define HAL_USE_CAN FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -82,9 +74,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_DAC) || defined(__DOXYGEN__)
|
||||
#if USE_DAC1 || USE_DAC2
|
||||
#define HAL_USE_DAC TRUE
|
||||
#define HAL_USE_DAC TRUE
|
||||
#else
|
||||
#define HAL_USE_DAC FALSE
|
||||
#define HAL_USE_DAC FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -107,9 +99,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__)
|
||||
#if USE_I2C1 || USE_I2C2 || USE_I2C3 || USE_I2C4
|
||||
#define HAL_USE_I2C TRUE
|
||||
#define HAL_USE_I2C TRUE
|
||||
#else
|
||||
#define HAL_USE_I2C FALSE
|
||||
#define HAL_USE_I2C FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -122,16 +114,12 @@
|
||||
|
||||
/**
|
||||
* @brief Enables the ICU subsystem.
|
||||
* NOTE: ICU is needed form PPM and Spektrum radio
|
||||
* Maybe also for Superbit. Leave default TRUE for now
|
||||
* Might have to be changed to
|
||||
* ifdef RADIO_CONTROL_TYPE_PPM then TRUE, otherwise FALSE
|
||||
*/
|
||||
#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
|
||||
#if RADIO_CONTROL_TYPE_PPM || USE_PWM_INPUT || defined USE_PWM_INPUT1 || defined USE_PWM_INPUT2
|
||||
#define HAL_USE_ICU TRUE
|
||||
#if RADIO_CONTROL_TYPE_PPM || USE_PWM_INPUT || defined(USE_PWM_INPUT1) || defined(USE_PWM_INPUT2)
|
||||
#define HAL_USE_ICU TRUE
|
||||
#else
|
||||
#define HAL_USE_ICU FALSE
|
||||
#define HAL_USE_ICU FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -175,9 +163,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__)
|
||||
#if USE_UART1 || USE_UART2 || USE_UART3 || USE_UART4 || USE_UART5 || USE_UART6 || USE_UART7 || USE_UART8
|
||||
#define HAL_USE_SERIAL TRUE
|
||||
#define HAL_USE_SERIAL TRUE
|
||||
#else
|
||||
#define HAL_USE_SERIAL FALSE
|
||||
#define HAL_USE_SERIAL FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -186,9 +174,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
|
||||
#if USE_USB_SERIAL
|
||||
#define HAL_USE_SERIAL_USB TRUE
|
||||
#define HAL_USE_SERIAL_USB TRUE
|
||||
#else
|
||||
#define HAL_USE_SERIAL_USB FALSE
|
||||
#define HAL_USE_SERIAL_USB FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -204,9 +192,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__)
|
||||
#if USE_SPI
|
||||
#define HAL_USE_SPI TRUE
|
||||
#define HAL_USE_SPI TRUE
|
||||
#else
|
||||
#define HAL_USE_SPI FALSE
|
||||
#define HAL_USE_SPI FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -229,9 +217,9 @@
|
||||
*/
|
||||
#if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
|
||||
#if USE_USB_SERIAL
|
||||
#define HAL_USE_USB TRUE
|
||||
#define HAL_USE_USB TRUE
|
||||
#else
|
||||
#define HAL_USE_USB FALSE
|
||||
#define HAL_USE_USB FALSE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -463,6 +451,26 @@
|
||||
#define SERIAL_BUFFERS_SIZE 1024
|
||||
#endif
|
||||
|
||||
/*===========================================================================*/
|
||||
/* SIO driver related settings. */
|
||||
/*===========================================================================*/
|
||||
|
||||
/**
|
||||
* @brief Default bit rate.
|
||||
* @details Configuration parameter, this is the baud rate selected for the
|
||||
* default configuration.
|
||||
*/
|
||||
#if !defined(SIO_DEFAULT_BITRATE) || defined(__DOXYGEN__)
|
||||
#define SIO_DEFAULT_BITRATE 38400
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Support for thread synchronization API.
|
||||
*/
|
||||
#if !defined(SIO_USE_SYNCHRONIZATION) || defined(__DOXYGEN__)
|
||||
#define SIO_USE_SYNCHRONIZATION TRUE
|
||||
#endif
|
||||
|
||||
/*===========================================================================*/
|
||||
/* SERIAL_USB driver related setting. */
|
||||
/*===========================================================================*/
|
||||
@@ -499,11 +507,10 @@
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables circular transfers APIs.
|
||||
* @note Disabling this option saves both code and data space.
|
||||
* @brief Inserts an assertion on function errors before returning.
|
||||
*/
|
||||
#if !defined(SPI_USE_CIRCULAR) || defined(__DOXYGEN__)
|
||||
#define SPI_USE_CIRCULAR FALSE
|
||||
#if !defined(SPI_USE_ASSERT_ON_ERROR) || defined(__DOXYGEN__)
|
||||
#define SPI_USE_ASSERT_ON_ERROR TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
|
||||
#if USE_HARD_FAULT_RECOVERY
|
||||
|
||||
#if defined STM32F4 || defined STM32F7
|
||||
#if defined(STM32F4XX) || defined (STM32F7XX)
|
||||
#define BCKP_SECTION ".ram5"
|
||||
#define IN_BCKP_SECTION(var) var __attribute__ ((section(BCKP_SECTION), aligned(8)))
|
||||
#else
|
||||
@@ -87,11 +87,11 @@ CH_IRQ_HANDLER(UsageFault_Handler)
|
||||
bool recovering_from_hard_fault;
|
||||
|
||||
// select correct register
|
||||
#if defined STM32F4
|
||||
#if defined(STM32F4XX)
|
||||
#define __PWR_CSR PWR->CSR
|
||||
#define __PWR_CSR_BRE PWR_CSR_BRE
|
||||
#define __PWR_CSR_BRR PWR_CSR_BRR
|
||||
#elif defined STM32F7
|
||||
#elif defined(STM32F7XX)
|
||||
#define __PWR_CSR PWR->CSR1
|
||||
#define __PWR_CSR_BRE PWR_CSR1_BRE
|
||||
#define __PWR_CSR_BRR PWR_CSR1_BRR
|
||||
@@ -108,11 +108,6 @@ bool recovering_from_hard_fault;
|
||||
*/
|
||||
void mcu_arch_init(void)
|
||||
{
|
||||
#if LUFTBOOT
|
||||
PRINT_CONFIG_MSG("We are running luftboot, the interrupt vector is being relocated.")
|
||||
SCB->VTOR = CORTEX_VTOR_INIT;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* System initializations.
|
||||
* - HAL initialization, this also initializes the configured device drivers
|
||||
@@ -125,11 +120,11 @@ void mcu_arch_init(void)
|
||||
|
||||
#if USE_HARD_FAULT_RECOVERY
|
||||
/* Backup domain SRAM enable, and with it, the regulator */
|
||||
#if defined STM32F4 || defined STM32F7
|
||||
#if defined(STM32F4XX) || defined(STM32F7XX)
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_BKPSRAMEN;
|
||||
__PWR_CSR |= __PWR_CSR_BRE;
|
||||
while ((__PWR_CSR & __PWR_CSR_BRR) == 0) ; /* Waits until the regulator is stable */
|
||||
#endif /* STM32F4 | STM32F7*/
|
||||
#endif /* STM32F4 | STM32F7 */
|
||||
|
||||
// test if last reset was a 'real' hard fault
|
||||
recovering_from_hard_fault = false;
|
||||
@@ -151,9 +146,21 @@ void mcu_arch_init(void)
|
||||
|
||||
}
|
||||
|
||||
void WEAK mcu_periph_energy_save(void)
|
||||
/**
|
||||
* @brief Save energy for performing operations on shutdown
|
||||
* Used for example to shutdown SD-card logging
|
||||
*/
|
||||
void mcu_periph_energy_save(void)
|
||||
{
|
||||
// Default empty implementation
|
||||
// see board.c file
|
||||
#if defined(ENERGY_SAVE_INPUTS)
|
||||
BOARD_GROUP_DECLFOREACH(input_line, ENERGY_SAVE_INPUTS) {
|
||||
palSetLineMode(input_line, PAL_MODE_INPUT);
|
||||
}
|
||||
#endif
|
||||
#if defined(ENERGY_SAVE_LOWS)
|
||||
BOARD_GROUP_DECLFOREACH(input_low, ENERGY_SAVE_LOWS) {
|
||||
palClearLine(input_low);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -51,16 +51,21 @@ extern bool recovering_from_hard_fault;
|
||||
*/
|
||||
static inline void mcu_deep_sleep(void)
|
||||
{
|
||||
#if defined STM32F4
|
||||
#if defined(STM32F4XX)
|
||||
/* clear PDDS and LPDS bits */
|
||||
PWR->CR &= ~(PWR_CR_PDDS | PWR_CR_LPDS);
|
||||
/* set LPDS and clear */
|
||||
PWR->CR |= (PWR_CR_LPDS | PWR_CR_CSBF | PWR_CR_CWUF);
|
||||
#elif defined STM32F7
|
||||
#elif defined(STM32F7XX)
|
||||
/* clear PDDS and LPDS bits */
|
||||
PWR->CR1 &= ~(PWR_CR1_PDDS | PWR_CR1_LPDS);
|
||||
/* set LPDS and clear */
|
||||
PWR->CR1 |= (PWR_CR1_LPDS | PWR_CR1_CSBF);
|
||||
#elif defined(STM32H7XX)
|
||||
/* clear LPDS */
|
||||
PWR->CR1 &= ~PWR_CR1_LPDS;
|
||||
/* set LPDS */
|
||||
PWR->CR1 |= PWR_CR1_LPDS;
|
||||
#endif
|
||||
|
||||
/* Setup the deepsleep mask */
|
||||
|
||||
@@ -48,7 +48,7 @@
|
||||
* Then only every second channel is really read. Might be fixed in next version
|
||||
* of ChibiOS
|
||||
*
|
||||
* V_ref is 3.3V, ADC has 12bit resolution.
|
||||
* V_ref is 3.3V, ADC has 12bit or 16bit resolution.
|
||||
*/
|
||||
#include "mcu_periph/adc.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
@@ -66,22 +66,16 @@
|
||||
///#endif
|
||||
|
||||
|
||||
// architecture dependent settings
|
||||
#if defined(__STM32F10x_H) || defined(__STM32F105xC_H) || defined (__STM32F107xC_H)
|
||||
// STM32F1xx
|
||||
#define ADC_SAMPLE_RATE ADC_SAMPLE_41P5
|
||||
#define ADC_CR2_CFG ADC_CR2_TSVREFE
|
||||
#elif defined(__STM32F4xx_H) || defined(__STM32F7xx_H)
|
||||
// STM32F4xx | STM32F7xx
|
||||
#define ADC_SAMPLE_RATE ADC_SAMPLE_480
|
||||
#define ADC_CR2_CFG ADC_CR2_SWSTART
|
||||
#elif defined(__STM32F373xC_H)
|
||||
#define ADC_SAMPLE_RATE ADC_SAMPLE_239P5
|
||||
#define ADC_CR2_CFG ADC_CR2_SWSTART
|
||||
#elif defined(__STM32F3xx_H)
|
||||
/* Set the default sample rate */
|
||||
#if !defined(ADC_SAMPLE_RATE)
|
||||
#if defined(STM32H7XX)
|
||||
#define ADC_SAMPLE_RATE ADC_SMPR_SMP_384P5
|
||||
#elif defined(STM32F3XX)
|
||||
#define ADC_SAMPLE_RATE ADC_SMPR_SMP_601P5
|
||||
#else
|
||||
#define ADC_SAMPLE_RATE ADC_SAMPLE_480
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
// Create channel map
|
||||
static const uint8_t adc_channel_map[ADC_NUM_CHANNELS] = {
|
||||
@@ -143,9 +137,10 @@ ADCDriver *adcp_err = NULL;
|
||||
#ifndef ADC_BUF_DEPTH
|
||||
#define ADC_BUF_DEPTH (MAX_AV_NB_SAMPLE/2)
|
||||
#endif
|
||||
static IN_DMA_SECTION(adcsample_t adc_samples[ADC_NUM_CHANNELS * ADC_BUF_DEPTH]);
|
||||
static IN_DMA_SECTION(adcsample_t adc_samples[ADC_NUM_CHANNELS * MAX_AV_NB_SAMPLE]);
|
||||
|
||||
#if USE_AD1
|
||||
static ADCConversionGroup adc1_group;
|
||||
static struct adc_buf *adc1_buffers[ADC_NUM_CHANNELS];
|
||||
static uint32_t adc1_sum_tmp[ADC_NUM_CHANNELS];
|
||||
static uint8_t adc1_samples_tmp[ADC_NUM_CHANNELS];
|
||||
@@ -167,46 +162,70 @@ static struct {
|
||||
} adc_watchdog;
|
||||
#endif
|
||||
|
||||
// From libopencm3
|
||||
static void adc_regular_sequence(uint32_t *sqr1, uint32_t *sqr2, uint32_t *sqr3, uint8_t length, const uint8_t channel[])
|
||||
/**
|
||||
* @brief Configure the ADC conversion group depending on the architecture
|
||||
*
|
||||
* @param cfg The configuration to be set
|
||||
* @param num_channels The number of channels in the ADC
|
||||
* @param channels The channel mapping to real channels
|
||||
* @param sample_rate The sample rate for all channels
|
||||
* @param end_cb The callback function at the end of conversion
|
||||
* @param error_cb The callback function whenever an error occurs
|
||||
*/
|
||||
static void adc_configure(ADCConversionGroup *cfg, uint8_t num_channels, const uint8_t channels[], uint32_t sample_rate,
|
||||
adccallback_t end_cb, adcerrorcallback_t error_cb)
|
||||
{
|
||||
uint32_t first6 = 0;
|
||||
uint32_t second6 = 0;
|
||||
uint32_t third6 = ADC_SQR1_NUM_CH(length);
|
||||
uint8_t i = 0;
|
||||
// Set the general configuration
|
||||
cfg->circular = true;
|
||||
cfg->num_channels = num_channels;
|
||||
cfg->end_cb = end_cb;
|
||||
cfg->error_cb = error_cb;
|
||||
|
||||
for (i = 1; i <= length; i++) {
|
||||
if (i <= 6) {
|
||||
first6 |= (channel[i - 1] << ((i - 1) * 5));
|
||||
// Set to 16bits by default else try 12bit
|
||||
#if defined(ADC_CFGR_RES_16BITS)
|
||||
cfg->cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS;
|
||||
#elif defined(ADC_CFGR_RES_12BITS)
|
||||
cfg->cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS;
|
||||
#else
|
||||
cfg->sqr1 = ADC_SQR1_NUM_CH(num_channels);
|
||||
cfg->cr2 = ADC_CR2_SWSTART;
|
||||
|
||||
#if defined(ADC_CR2_TSVREFE)
|
||||
cfg->cr2 |= ADC_CR2_TSVREFE;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Go through all the channels
|
||||
for (uint8_t i = 0; i < num_channels; i++) {
|
||||
uint8_t chan = channels[i];
|
||||
|
||||
#if defined(STM32H7XX) || defined(STM32F3XX) || defined(STM32G4XX) || defined(STM32L4XX)
|
||||
cfg->pcsel |= (1 << chan);
|
||||
cfg->smpr[chan / 10] |= sample_rate << (3 << (chan % 10));
|
||||
|
||||
if (i < 4) {
|
||||
cfg->sqr[0] |= chan << (6 * (i + 1));
|
||||
} else if (i < 9) {
|
||||
cfg->sqr[1] |= chan << (6 * (i - 4));
|
||||
} else {
|
||||
cfg->sqr[2] |= chan << (6 * (i - 9));
|
||||
}
|
||||
if ((i > 6) && (i <= 12)) {
|
||||
second6 |= (channel[i - 1] << ((i - 6 - 1) * 5));
|
||||
#else
|
||||
if (chan < 10) {
|
||||
cfg->smpr2 |= sample_rate << (3 * chan);
|
||||
} else {
|
||||
cfg->smpr1 |= sample_rate << (3 * (chan - 10));
|
||||
}
|
||||
if ((i > 12) && (i <= 18)) {
|
||||
third6 |= (channel[i - 1] << ((i - 12 - 1) * 5));
|
||||
|
||||
if (i < 6) {
|
||||
cfg->sqr3 |= chan << (5 * i);
|
||||
} else if (i < 12) {
|
||||
cfg->sqr2 |= chan << (5 * (i - 6));
|
||||
} else {
|
||||
cfg->sqr3 |= chan << (5 * (i - 12));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
*sqr3 = first6;
|
||||
*sqr2 = second6;
|
||||
*sqr1 = third6;
|
||||
}
|
||||
|
||||
// From libopencm3
|
||||
static void adc_sample_time_on_all_channels(uint32_t *smpr1, uint32_t *smpr2, uint8_t time)
|
||||
{
|
||||
uint8_t i;
|
||||
uint32_t reg32 = 0;
|
||||
|
||||
for (i = 0; i <= 9; i++) {
|
||||
reg32 |= (time << (i * 3));
|
||||
}
|
||||
*smpr2 = reg32;
|
||||
|
||||
reg32 = 0;
|
||||
for (i = 10; i <= 17; i++) {
|
||||
reg32 |= (time << ((i - 10) * 3));
|
||||
}
|
||||
*smpr1 = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -231,7 +250,8 @@ void adc1callback(ADCDriver *adcp)
|
||||
// half buffer start in the middle of buffer, else, is start at
|
||||
// beginiing of buffer
|
||||
const adcsample_t *buffer = adc_samples + (adcIsBufferComplete(adcp) ?
|
||||
n * ADC_NUM_CHANNELS : 0U);
|
||||
n *ADC_NUM_CHANNELS : 0U);
|
||||
cacheBufferInvalidate(adc_samples, sizeof(adc_samples));
|
||||
|
||||
for (int channel = 0; channel < ADC_NUM_CHANNELS; channel++) {
|
||||
if (adc1_buffers[channel] != NULL) {
|
||||
@@ -304,12 +324,6 @@ void adc_buf_channel(uint8_t adc_channel, struct adc_buf *s, uint8_t av_nb_sampl
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Configuration structure
|
||||
* must be global
|
||||
*/
|
||||
static ADCConversionGroup adcgrpcfg;
|
||||
|
||||
/**
|
||||
* Adc init
|
||||
*
|
||||
@@ -356,13 +370,6 @@ void adc_init(void)
|
||||
gpio_setup_pin_analog(ADC_9_GPIO_PORT, ADC_9_GPIO_PIN);
|
||||
#endif
|
||||
|
||||
// Configuration register
|
||||
uint32_t sqr1, sqr2, sqr3;
|
||||
adc_regular_sequence(&sqr1, &sqr2, &sqr3, ADC_NUM_CHANNELS, adc_channel_map);
|
||||
|
||||
uint32_t smpr1, smpr2;
|
||||
adc_sample_time_on_all_channels(&smpr1, &smpr2, ADC_SAMPLE_RATE);
|
||||
|
||||
#if USE_ADC_WATCHDOG
|
||||
adc_watchdog.adc = NULL;
|
||||
adc_watchdog.cb = NULL;
|
||||
@@ -370,42 +377,12 @@ void adc_init(void)
|
||||
adc_watchdog.vmin = (1 << 12) - 1; // max adc
|
||||
#endif
|
||||
|
||||
adcgrpcfg.circular = TRUE;
|
||||
adcgrpcfg.num_channels = ADC_NUM_CHANNELS;
|
||||
adcgrpcfg.end_cb = adc1callback;
|
||||
adcgrpcfg.error_cb = adcerrorcallback;
|
||||
#if defined(__STM32F373xC_H)
|
||||
adcgrpcfg.u.adc.smpr[0] = smpr1;
|
||||
adcgrpcfg.u.adc.smpr[1] = smpr2;
|
||||
adcgrpcfg.u.adc.sqr[0] = sqr1;
|
||||
adcgrpcfg.u.adc.sqr[1] = sqr2;
|
||||
adcgrpcfg.u.adc.sqr[2] = sqr3;
|
||||
adcgrpcfg.u.adc.cr1 = 0;
|
||||
adcgrpcfg.u.adc.cr2 = ADC_CR2_CFG;
|
||||
#elif defined(__STM32F3xx_H)
|
||||
//TODO: check if something needs to be done with the other regs (can be found in ~/paparazzi/sw/ext/chibios/os/hal/ports/STM32/LLD/ADCv3)
|
||||
#warning ADCs not tested with stm32f30
|
||||
// cfgr
|
||||
// tr1
|
||||
|
||||
adcgrpcfg.smpr[0] = smpr1; // is this even correct?
|
||||
adcgrpcfg.smpr[1] = smpr2;
|
||||
adcgrpcfg.sqr[0] = sqr1;
|
||||
adcgrpcfg.sqr[1] = sqr2;
|
||||
adcgrpcfg.sqr[2] = sqr3;
|
||||
#else
|
||||
adcgrpcfg.cr2 = ADC_CR2_CFG;
|
||||
adcgrpcfg.cr1 = 0;
|
||||
adcgrpcfg.smpr1 = smpr1;
|
||||
adcgrpcfg.smpr2 = smpr2;
|
||||
adcgrpcfg.sqr1 = sqr1;
|
||||
adcgrpcfg.sqr2 = sqr2;
|
||||
adcgrpcfg.sqr3 = sqr3;
|
||||
#endif
|
||||
// Configure the ADC structure
|
||||
adc_configure(&adc1_group, ADC_NUM_CHANNELS, adc_channel_map, ADC_SAMPLE_RATE, adc1callback, adcerrorcallback);
|
||||
|
||||
// Start ADC in continious conversion mode
|
||||
adcStart(&ADCD1, NULL);
|
||||
adcStartConversion(&ADCD1, &adcgrpcfg, adc_samples, ADC_BUF_DEPTH);
|
||||
adcStartConversion(&ADCD1, &adc1_group, adc_samples, ADC_BUF_DEPTH);
|
||||
}
|
||||
|
||||
#if USE_ADC_WATCHDOG
|
||||
|
||||
@@ -110,7 +110,7 @@ typedef void (*adc_watchdog_callback)(void);
|
||||
* @param cb callback function call within ISR locked zone
|
||||
*/
|
||||
extern void register_adc_watchdog(ADCDriver *adc, adc_channels_num_t channel, adcsample_t vmin,
|
||||
adc_watchdog_callback cb);
|
||||
adc_watchdog_callback cb);
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
@@ -62,14 +62,14 @@ void gpio_setup_pin_af(ioportid_t port, uint16_t pin, uint8_t af, bool is_output
|
||||
{
|
||||
chSysLock();
|
||||
// architecture dependent settings
|
||||
#if defined(STM32F1)
|
||||
#if defined(STM32F1XX)
|
||||
// FIXME: STM32F1xx doesn't support several alternate modes, is it needed for drivers?
|
||||
(void)port;
|
||||
(void)pin;
|
||||
(void)af;
|
||||
(void)is_output;
|
||||
#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F7)
|
||||
// STM32F4xx, STM32F3xx and STM32F7xx
|
||||
#else
|
||||
// STM32F4xx, STM32F3xx, STM32F7xx and STM32H7xx
|
||||
if (af) {
|
||||
palSetPadMode(port, pin, PAL_MODE_ALTERNATE(af));
|
||||
} else {
|
||||
|
||||
@@ -56,11 +56,13 @@ static void i2c_chibios_setbitrate(struct i2c_periph *p, int bitrate) __attribut
|
||||
|
||||
// private I2C init structure
|
||||
struct i2c_init {
|
||||
semaphore_t *sem;
|
||||
I2CConfig *cfg;
|
||||
#ifdef STM32F7
|
||||
uint8_t *dma_buf;
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
uint8_t dma_buf[I2C_BUF_LEN];
|
||||
#endif
|
||||
char *name;
|
||||
semaphore_t sem;
|
||||
I2CConfig cfg;
|
||||
struct i2c_errors errors;
|
||||
};
|
||||
|
||||
|
||||
@@ -79,7 +81,7 @@ static void handle_i2c_thd(struct i2c_periph *p)
|
||||
struct i2c_init *i = (struct i2c_init *) p->init_struct;
|
||||
|
||||
// wait for a transaction to be pushed in the queue
|
||||
chSemWait(i->sem);
|
||||
chSemWait(&i->sem);
|
||||
|
||||
if (p->trans_insert_idx == p->trans_extract_idx) {
|
||||
p->status = I2CIdle;
|
||||
@@ -94,15 +96,17 @@ static void handle_i2c_thd(struct i2c_periph *p)
|
||||
msg_t status;
|
||||
// submit i2c transaction (R/W or R only depending of len_w)
|
||||
if (t->len_w > 0) {
|
||||
#if defined STM32F7
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
// we do stupid mem copy because F7 needs a special RAM for DMA operation
|
||||
memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w));
|
||||
cacheBufferFlush(i->dma_buf, t->len_w);
|
||||
status = i2cMasterTransmitTimeout(
|
||||
(I2CDriver *)p->reg_addr,
|
||||
(i2caddr_t)((t->slave_addr) >> 1),
|
||||
(uint8_t *)i->dma_buf, (size_t)(t->len_w),
|
||||
(uint8_t *)i->dma_buf, (size_t)(t->len_r),
|
||||
tmo);
|
||||
cacheBufferInvalidate(i->dma_buf, t->len_r);
|
||||
memcpy((void *)t->buf, i->dma_buf, (size_t)(t->len_r));
|
||||
#else
|
||||
status = i2cMasterTransmitTimeout(
|
||||
@@ -113,7 +117,7 @@ static void handle_i2c_thd(struct i2c_periph *p)
|
||||
tmo);
|
||||
#endif
|
||||
} else {
|
||||
#if defined STM32F7
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
// we do stupid mem copy because F7 needs a special RAM for DMA operation
|
||||
memcpy(i->dma_buf, (void *)t->buf, (size_t)(t->len_w));
|
||||
status = i2cMasterReceiveTimeout(
|
||||
@@ -150,7 +154,7 @@ static void handle_i2c_thd(struct i2c_periph *p)
|
||||
//if a timeout occurred before operation end
|
||||
// mark as failed and restart
|
||||
t->status = I2CTransFailed;
|
||||
i2cStart((I2CDriver *)p->reg_addr, i->cfg);
|
||||
i2cStart((I2CDriver *)p->reg_addr, &i->cfg);
|
||||
break;
|
||||
case MSG_RESET:
|
||||
//if one or more I2C errors occurred, the errors can
|
||||
@@ -183,31 +187,32 @@ static void handle_i2c_thd(struct i2c_periph *p)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief I2C thead
|
||||
*
|
||||
* @param arg The i2c peripheral (i2c_periph)
|
||||
*/
|
||||
static void thd_i2c(void *arg)
|
||||
{
|
||||
struct i2c_periph *i2cp = (struct i2c_periph *)arg;
|
||||
struct i2c_init *init_s = (struct i2c_init *)i2cp->init_struct;
|
||||
chRegSetThreadName(init_s->name);
|
||||
|
||||
while (TRUE) {
|
||||
handle_i2c_thd(i2cp);
|
||||
}
|
||||
}
|
||||
#endif /* USE_I2C1 || USE_I2C2 || USE_I2C3 || USE_I2C4 */
|
||||
|
||||
#if USE_I2C1
|
||||
// I2C1 config
|
||||
PRINT_CONFIG_VAR(I2C1_CLOCK_SPEED)
|
||||
static SEMAPHORE_DECL(i2c1_sem, 0);
|
||||
static I2CConfig i2cfg1 = I2C1_CFG_DEF;
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t i2c1_dma_buf[I2C_BUF_LEN]);
|
||||
static struct i2c_init i2c1_init_s = {
|
||||
.sem = &i2c1_sem,
|
||||
.cfg = &i2cfg1,
|
||||
.dma_buf = i2c1_dma_buf
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct i2c_init i2c1_init_s) = {
|
||||
.name = "i2c1",
|
||||
.sem = __SEMAPHORE_DATA(i2c1_init_s.sem, 0),
|
||||
.cfg = I2C1_CFG_DEF
|
||||
};
|
||||
#else
|
||||
static struct i2c_init i2c1_init_s = {
|
||||
.sem = &i2c1_sem,
|
||||
.cfg = &i2cfg1
|
||||
};
|
||||
#endif
|
||||
// Errors
|
||||
struct i2c_errors i2c1_errors;
|
||||
// Thread
|
||||
static __attribute__((noreturn)) void thd_i2c1(void *arg);
|
||||
static THD_WORKING_AREA(wa_thd_i2c1, I2C_THREAD_STACK_SIZE);
|
||||
|
||||
/*
|
||||
@@ -219,53 +224,24 @@ void i2c1_hw_init(void)
|
||||
i2c1.submit = i2c_chibios_submit;
|
||||
i2c1.setbitrate = i2c_chibios_setbitrate;
|
||||
|
||||
i2cStart(&I2CD1, &i2cfg1);
|
||||
i2cStart(&I2CD1, &i2c1_init_s.cfg);
|
||||
i2c1.reg_addr = &I2CD1;
|
||||
i2c1.errors = &i2c1_errors;
|
||||
i2c1.errors = &i2c1_init_s.errors;
|
||||
i2c1.init_struct = &i2c1_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_i2c1, sizeof(wa_thd_i2c1),
|
||||
NORMALPRIO + 1, thd_i2c1, NULL);
|
||||
}
|
||||
|
||||
/*
|
||||
* I2C1 thread
|
||||
*
|
||||
*/
|
||||
static void thd_i2c1(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("i2c1");
|
||||
|
||||
while (TRUE) {
|
||||
handle_i2c_thd(&i2c1);
|
||||
}
|
||||
NORMALPRIO + 1, thd_i2c, (void *)&i2c1);
|
||||
}
|
||||
#endif /* USE_I2C1 */
|
||||
|
||||
#if USE_I2C2
|
||||
// I2C2 config
|
||||
PRINT_CONFIG_VAR(I2C2_CLOCK_SPEED)
|
||||
static SEMAPHORE_DECL(i2c2_sem, 0);
|
||||
static I2CConfig i2cfg2 = I2C2_CFG_DEF;
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t i2c2_dma_buf[I2C_BUF_LEN]);
|
||||
static struct i2c_init i2c2_init_s = {
|
||||
.sem = &i2c2_sem,
|
||||
.cfg = &i2cfg2,
|
||||
.dma_buf = i2c2_dma_buf
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct i2c_init i2c2_init_s) = {
|
||||
.name = "i2c2",
|
||||
.sem = __SEMAPHORE_DATA(i2c2_init_s.sem, 0),
|
||||
.cfg = I2C2_CFG_DEF
|
||||
};
|
||||
#else
|
||||
static struct i2c_init i2c2_init_s = {
|
||||
.sem = &i2c2_sem,
|
||||
.cfg = &i2cfg2
|
||||
};
|
||||
#endif
|
||||
// Errors
|
||||
struct i2c_errors i2c2_errors;
|
||||
// Thread
|
||||
static __attribute__((noreturn)) void thd_i2c2(void *arg);
|
||||
static THD_WORKING_AREA(wa_thd_i2c2, I2C_THREAD_STACK_SIZE);
|
||||
|
||||
/*
|
||||
@@ -277,53 +253,24 @@ void i2c2_hw_init(void)
|
||||
i2c2.submit = i2c_chibios_submit;
|
||||
i2c2.setbitrate = i2c_chibios_setbitrate;
|
||||
|
||||
i2cStart(&I2CD2, &i2cfg2);
|
||||
i2cStart(&I2CD2, &i2c2_init_s.cfg);
|
||||
i2c2.reg_addr = &I2CD2;
|
||||
i2c2.errors = &i2c2_errors;
|
||||
i2c2.errors = &i2c2_init_s.errors;
|
||||
i2c2.init_struct = &i2c2_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_i2c2, sizeof(wa_thd_i2c2),
|
||||
NORMALPRIO + 1, thd_i2c2, NULL);
|
||||
}
|
||||
|
||||
/*
|
||||
* I2C2 thread
|
||||
*
|
||||
*/
|
||||
static void thd_i2c2(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("i2c2");
|
||||
|
||||
while (TRUE) {
|
||||
handle_i2c_thd(&i2c2);
|
||||
}
|
||||
NORMALPRIO + 1, thd_i2c, (void *)&i2c2);
|
||||
}
|
||||
#endif /* USE_I2C2 */
|
||||
|
||||
#if USE_I2C3
|
||||
// I2C3 config
|
||||
PRINT_CONFIG_VAR(I2C3_CLOCK_SPEED)
|
||||
static SEMAPHORE_DECL(i2c3_sem, 0);
|
||||
static I2CConfig i2cfg3 = I2C3_CFG_DEF;
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t i2c3_dma_buf[I2C_BUF_LEN]);
|
||||
static struct i2c_init i2c3_init_s = {
|
||||
.sem = &i2c3_sem,
|
||||
.cfg = &i2cfg3,
|
||||
.dma_buf = i2c3_dma_buf
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct i2c_init i2c3_init_s) = {
|
||||
.name = "i2c3",
|
||||
.sem = __SEMAPHORE_DATA(i2c3_init_s.sem, 0),
|
||||
.cfg = I2C3_CFG_DEF
|
||||
};
|
||||
#else
|
||||
static struct i2c_init i2c3_init_s = {
|
||||
.sem = &i2c3_sem,
|
||||
.cfg = &i2cfg3
|
||||
};
|
||||
#endif
|
||||
// Errors
|
||||
struct i2c_errors i2c3_errors;
|
||||
// Thread
|
||||
static __attribute__((noreturn)) void thd_i2c3(void *arg);
|
||||
static THD_WORKING_AREA(wa_thd_i2c3, I2C_THREAD_STACK_SIZE);
|
||||
|
||||
/*
|
||||
@@ -335,54 +282,24 @@ void i2c3_hw_init(void)
|
||||
i2c3.submit = i2c_chibios_submit;
|
||||
i2c3.setbitrate = i2c_chibios_setbitrate;
|
||||
|
||||
i2cStart(&I2CD3, &i2cfg3);
|
||||
i2cStart(&I2CD3, &i2c3_init_s.cfg);
|
||||
i2c3.reg_addr = &I2CD3;
|
||||
i2c3.init_struct = NULL;
|
||||
i2c3.errors = &i2c3_errors;
|
||||
i2c3.errors = &i2c3_init_s.errors;
|
||||
i2c3.init_struct = &i2c3_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_i2c3, sizeof(wa_thd_i2c3),
|
||||
NORMALPRIO + 1, thd_i2c3, NULL);
|
||||
}
|
||||
|
||||
/*
|
||||
* I2C3 thread
|
||||
*
|
||||
*/
|
||||
static void thd_i2c3(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("i2c3");
|
||||
|
||||
while (TRUE) {
|
||||
handle_i2c_thd(&i2c3);
|
||||
}
|
||||
NORMALPRIO + 1, thd_i2c, (void *)&i2c3);
|
||||
}
|
||||
#endif /* USE_I2C3 */
|
||||
|
||||
#if USE_I2C4
|
||||
// I2C4 config
|
||||
PRINT_CONFIG_VAR(I2C4_CLOCK_SPEED)
|
||||
static SEMAPHORE_DECL(i2c4_sem, 0);
|
||||
static I2CConfig i2cfg4 = I2C4_CFG_DEF;
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t i2c4_dma_buf[I2C_BUF_LEN]);
|
||||
static struct i2c_init i2c4_init_s = {
|
||||
.sem = &i2c4_sem,
|
||||
.cfg = &i2cfg4,
|
||||
.dma_buf = i2c4_dma_buf
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct i2c_init i2c4_init_s) = {
|
||||
.name = "i2c4",
|
||||
.sem = __SEMAPHORE_DATA(i2c4_init_s.sem, 0),
|
||||
.cfg = I2C4_CFG_DEF
|
||||
};
|
||||
#else
|
||||
static struct i2c_init i2c4_init_s = {
|
||||
.sem = &i2c4_sem,
|
||||
.cfg = &i2cfg4
|
||||
};
|
||||
#endif
|
||||
// Errors
|
||||
struct i2c_errors i2c4_errors;
|
||||
// Thread
|
||||
static __attribute__((noreturn)) void thd_i2c4(void *arg);
|
||||
static THD_WORKING_AREA(wa_thd_i2c4, I2C_THREAD_STACK_SIZE);
|
||||
|
||||
/*
|
||||
@@ -394,28 +311,13 @@ void i2c4_hw_init(void)
|
||||
i2c4.submit = i2c_chibios_submit;
|
||||
i2c4.setbitrate = i2c_chibios_setbitrate;
|
||||
|
||||
i2cStart(&I2CD4, &i2cfg4);
|
||||
i2cStart(&I2CD4, &i2c4_init_s.cfg);
|
||||
i2c4.reg_addr = &I2CD4;
|
||||
i2c4.init_struct = NULL;
|
||||
i2c4.errors = &i2c4_errors;
|
||||
i2c4.errors = &i2c4_init_s.errors;
|
||||
i2c4.init_struct = &i2c4_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_i2c4, sizeof(wa_thd_i2c4),
|
||||
NORMALPRIO + 1, thd_i2c4, NULL);
|
||||
}
|
||||
|
||||
/*
|
||||
* I2C4 thread
|
||||
*
|
||||
*/
|
||||
static void thd_i2c4(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("i2c4");
|
||||
|
||||
while (TRUE) {
|
||||
handle_i2c_thd(&i2c4);
|
||||
}
|
||||
NORMALPRIO + 1, thd_i2c, (void *)&i2c4);
|
||||
}
|
||||
#endif /* USE_I2C4 */
|
||||
|
||||
@@ -475,7 +377,7 @@ static bool i2c_chibios_submit(struct i2c_periph *p, struct i2c_transaction *t)
|
||||
p->trans_insert_idx = temp;
|
||||
|
||||
chSysUnlock();
|
||||
chSemSignal(((struct i2c_init *)p->init_struct)->sem);
|
||||
chSemSignal(&((struct i2c_init *)p->init_struct)->sem);
|
||||
// transaction submitted
|
||||
return TRUE;
|
||||
#else
|
||||
|
||||
@@ -43,24 +43,33 @@
|
||||
#ifndef RAM_ARCH_H
|
||||
#define RAM_ARCH_H
|
||||
|
||||
#if defined STM32F1
|
||||
#if defined(STM32F1XX)
|
||||
#define STD_SECTION ".ram0"
|
||||
#define FAST_SECTION ".ram0"
|
||||
#define DMA_SECTION ".ram0"
|
||||
#elif defined STM32F3
|
||||
#define DMA_ALIGN 8
|
||||
#elif defined(STM32F3XX)
|
||||
#define STD_SECTION ".ram0"
|
||||
#define FAST_SECTION ".ram4"
|
||||
#define DMA_SECTION ".ram0"
|
||||
#elif defined STM32F4
|
||||
#define DMA_ALIGN 8
|
||||
#elif defined(STM32F4XX)
|
||||
#define STD_SECTION ".ram0"
|
||||
#define FAST_SECTION ".ram4"
|
||||
#define DMA_SECTION ".ram0"
|
||||
#elif defined STM32F7
|
||||
#define DMA_ALIGN 8
|
||||
#elif defined(STM32F7XX)
|
||||
#define STD_SECTION ".ram0"
|
||||
#define FAST_SECTION ".ram0"
|
||||
#define DMA_SECTION ".ram3"
|
||||
#define DMA_ALIGN 8
|
||||
#elif defined(STM32H7XX)
|
||||
#define STD_SECTION ".ram1"
|
||||
#define FAST_SECTION ".ram5"
|
||||
#define DMA_SECTION ".ram0"
|
||||
#define DMA_ALIGN 32
|
||||
#else
|
||||
#error "section defined only for STM32F1, STM32F4 and STM32F7"
|
||||
#error "section defined only for STM32F1, STM32F3, STM32F4, STM32F7 and STM32H7"
|
||||
#endif
|
||||
|
||||
#define IN_STD_SECTION_NOINIT(var) var __attribute__ ((section(STD_SECTION), aligned(8)))
|
||||
@@ -71,9 +80,9 @@
|
||||
#define IN_FAST_SECTION_CLEAR(var) var __attribute__ ((section(FAST_SECTION "_clear"), aligned(8)))
|
||||
#define IN_FAST_SECTION(var) var __attribute__ ((section(FAST_SECTION "_init"), aligned(8)))
|
||||
|
||||
#define IN_DMA_SECTION_NOINIT(var) var __attribute__ ((section(DMA_SECTION), aligned(8)))
|
||||
#define IN_DMA_SECTION_CLEAR(var) var __attribute__ ((section(DMA_SECTION "_clear"), aligned(8)))
|
||||
#define IN_DMA_SECTION(var) var __attribute__ ((section(DMA_SECTION "_init"), aligned(8)))
|
||||
#define IN_DMA_SECTION_NOINIT(var) var __attribute__ ((section(DMA_SECTION), aligned(DMA_ALIGN)))
|
||||
#define IN_DMA_SECTION_CLEAR(var) var __attribute__ ((section(DMA_SECTION "_clear"), aligned(DMA_ALIGN)))
|
||||
#define IN_DMA_SECTION(var) var __attribute__ ((section(DMA_SECTION "_init"), aligned(DMA_ALIGN)))
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ static enum {STOP, CONNECT} cnxState = STOP;
|
||||
|
||||
bool sdio_connect(void)
|
||||
{
|
||||
if (!sdc_lld_is_card_inserted (NULL)) {
|
||||
if (!sdc_lld_is_card_inserted(NULL)) {
|
||||
return FALSE;
|
||||
}
|
||||
|
||||
@@ -55,49 +55,36 @@ bool sdio_connect(void)
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
/*
|
||||
* Initializes the SDIO drivers.
|
||||
*
|
||||
* FIXME This could be hardcoded in board file ?
|
||||
*/
|
||||
const uint32_t mode = PAL_MODE_ALTERNATE(SDIO_AF) | PAL_STM32_OTYPE_PUSHPULL |
|
||||
PAL_STM32_OSPEED_HIGHEST | PAL_STM32_PUPDR_FLOATING | PAL_STM32_MODE_ALTERNATE;
|
||||
|
||||
palSetPadMode (SDIO_D0_PORT, SDIO_D0_PIN, mode | PAL_STM32_PUPDR_PULLUP);
|
||||
palSetPadMode (SDIO_D1_PORT, SDIO_D1_PIN, mode | PAL_STM32_PUPDR_PULLUP);
|
||||
palSetPadMode (SDIO_D2_PORT, SDIO_D2_PIN, mode | PAL_STM32_PUPDR_PULLUP);
|
||||
palSetPadMode (SDIO_D3_PORT, SDIO_D3_PIN, mode | PAL_STM32_PUPDR_PULLUP);
|
||||
palSetPadMode (SDIO_CK_PORT, SDIO_CK_PIN, mode);
|
||||
palSetPadMode (SDIO_CMD_PORT, SDIO_CMD_PIN, mode | PAL_STM32_PUPDR_PULLUP);
|
||||
// palSetPadMode (GPIOD, GPIOD_SDIO_CMD, mode);
|
||||
|
||||
chThdSleepMilliseconds(100);
|
||||
|
||||
|
||||
sdcStart(&SDCD1, NULL);
|
||||
while (sdcConnect(&SDCD1) != HAL_SUCCESS) {
|
||||
// Try only 3 times to prevent hanging
|
||||
for (uint8_t i = 0; i < 3; i++) {
|
||||
sdcStart(&SDCD1, NULL);
|
||||
if (sdcConnect(&SDCD1) == HAL_SUCCESS) {
|
||||
cnxState = CONNECT;
|
||||
return TRUE;
|
||||
}
|
||||
sdcStop(&SDCD1);
|
||||
chThdSleepMilliseconds(100);
|
||||
}
|
||||
|
||||
cnxState = CONNECT;
|
||||
return TRUE;
|
||||
return FALSE;
|
||||
}
|
||||
|
||||
|
||||
bool sdio_disconnect(void)
|
||||
{
|
||||
if (cnxState == STOP)
|
||||
if (cnxState == STOP) {
|
||||
return TRUE;
|
||||
}
|
||||
if (sdcDisconnect(&SDCD1)) {
|
||||
return FALSE;
|
||||
}
|
||||
sdcStop (&SDCD1);
|
||||
sdcStop(&SDCD1);
|
||||
cnxState = STOP;
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
bool is_card_inserted(void)
|
||||
{
|
||||
return sdc_lld_is_card_inserted (NULL);
|
||||
return sdc_lld_is_card_inserted(NULL);
|
||||
}
|
||||
|
||||
|
||||
@@ -35,8 +35,9 @@
|
||||
#include <string.h>
|
||||
#include "mcu_periph/ram_arch.h"
|
||||
|
||||
|
||||
#if SPI_SLAVE
|
||||
#error "ChibiOS operates only in SPI_MASTER mode"
|
||||
#error "ChibiOS operates only in SPI_MASTER mode (Slave is TODO)"
|
||||
#endif
|
||||
|
||||
#if USE_SPI0
|
||||
@@ -48,15 +49,20 @@
|
||||
#define SPI_THREAD_STACK_SIZE 512
|
||||
#endif
|
||||
|
||||
// Default spi DMA buffer length for F7/H7
|
||||
#ifndef SPI_DMA_BUF_LEN
|
||||
#define SPI_DMA_BUF_LEN 512 // it has to be big enough
|
||||
#endif
|
||||
|
||||
// private SPI init structure
|
||||
struct spi_init {
|
||||
semaphore_t *sem;
|
||||
#ifdef STM32F7
|
||||
uint8_t *dma_buf_out;
|
||||
uint8_t *dma_buf_in;
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
uint8_t dma_buf_out[SPI_DMA_BUF_LEN];
|
||||
uint8_t dma_buf_in[SPI_DMA_BUF_LEN];
|
||||
#endif
|
||||
char *name;
|
||||
semaphore_t sem;
|
||||
};
|
||||
#define SPI_DMA_BUF_LEN 512 // it has to be big enough
|
||||
|
||||
/**
|
||||
* Resolve slave port
|
||||
@@ -99,6 +105,21 @@ static inline ioportid_t spi_resolve_slave_port(uint8_t slave)
|
||||
return SPI_SELECT_SLAVE5_PORT;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE5
|
||||
#if USE_SPI_SLAVE6
|
||||
case 6:
|
||||
return SPI_SELECT_SLAVE6_PORT;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE6
|
||||
#if USE_SPI_SLAVE7
|
||||
case 7:
|
||||
return SPI_SELECT_SLAVE7_PORT;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE7
|
||||
#if USE_SPI_SLAVE8
|
||||
case 8:
|
||||
return SPI_SELECT_SLAVE8_PORT;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE8
|
||||
default:
|
||||
return 0;
|
||||
break;
|
||||
@@ -146,6 +167,21 @@ static inline uint16_t spi_resolve_slave_pin(uint8_t slave)
|
||||
return SPI_SELECT_SLAVE5_PIN;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE5
|
||||
#if USE_SPI_SLAVE6
|
||||
case 6:
|
||||
return SPI_SELECT_SLAVE6_PIN;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE6
|
||||
#if USE_SPI_SLAVE7
|
||||
case 7:
|
||||
return SPI_SELECT_SLAVE7_PIN;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE7
|
||||
#if USE_SPI_SLAVE8
|
||||
case 8:
|
||||
return SPI_SELECT_SLAVE8_PIN;
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE8
|
||||
default:
|
||||
return 0;
|
||||
break;
|
||||
@@ -153,26 +189,26 @@ static inline uint16_t spi_resolve_slave_pin(uint8_t slave)
|
||||
}
|
||||
|
||||
/**
|
||||
* Resolve CR1
|
||||
* Resolve CR1 (or CFG1)
|
||||
*
|
||||
* Given the transaction settings, returns the right configuration of
|
||||
* SPIx_CR1 register.
|
||||
*
|
||||
* This function is currently architecture dependent (for STM32F1xx
|
||||
* STM32F4xx and STM32F7xx only)
|
||||
* STM32F4xx, STM32F7xx and STM32H7xx only)
|
||||
* TODO: extend for other architectures too
|
||||
*
|
||||
* @param[in] t pointer to a @p spi_transaction struct
|
||||
*/
|
||||
static inline uint16_t spi_resolve_CR1(struct spi_transaction *t __attribute__((unused)))
|
||||
static inline uint32_t spi_resolve_CR1(struct spi_transaction *t __attribute__((unused)))
|
||||
{
|
||||
uint16_t CR1 = 0;
|
||||
#if defined(STM32F1) || defined(STM32F4)
|
||||
uint32_t CR1 = 0;
|
||||
#if defined(STM32F1XX) || defined(STM32F4XX)
|
||||
if (t->dss == SPIDss16bit) {
|
||||
CR1 |= SPI_CR1_DFF; // FIXME for F7
|
||||
CR1 |= SPI_CR1_DFF;
|
||||
}
|
||||
#endif
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7)
|
||||
#if defined(STM32F1XX) || defined(STM32F4XX) || defined(STM32F7XX)
|
||||
if (t->bitorder == SPILSBFirst) {
|
||||
CR1 |= SPI_CR1_LSBFIRST;
|
||||
}
|
||||
@@ -210,32 +246,51 @@ static inline uint16_t spi_resolve_CR1(struct spi_transaction *t __attribute__((
|
||||
default:
|
||||
break;
|
||||
}
|
||||
#endif /* STM32F1 || STM32F4 || STM32F7 */
|
||||
#endif /* STM32F1XX || STM32F4XX || STM32F7XX */
|
||||
#if defined(STM32H7XX)
|
||||
if (t->dss == SPIDss16bit) {
|
||||
CR1 |= SPI_CFG1_DSIZE_VALUE(15); // 16 bit transfer
|
||||
} else {
|
||||
CR1 |= SPI_CFG1_DSIZE_VALUE(7); // 8 bit transfer
|
||||
}
|
||||
CR1 |= SPI_CFG1_MBR_VALUE(t->cdiv);
|
||||
#endif /* STM32H7XX */
|
||||
return CR1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Resolve CR2
|
||||
* Resolve CR2 (or CFG2)
|
||||
*
|
||||
* Given the transaction settings, returns the right configuration of
|
||||
* SPIx_CR2 register.
|
||||
*
|
||||
* This function is currently architecture dependent (for STM32F1xx
|
||||
* STM32F4xx and STM32F7xx only)
|
||||
* STM32F4xx, STM32F7xx and STM32H7xx only)
|
||||
* TODO: extend for other architectures too
|
||||
*
|
||||
* @param[in] t pointer to a @p spi_transaction struct
|
||||
*/
|
||||
static inline uint16_t spi_resolve_CR2(struct spi_transaction *t __attribute__((unused)))
|
||||
static inline uint32_t spi_resolve_CR2(struct spi_transaction *t __attribute__((unused)))
|
||||
{
|
||||
uint16_t CR2 = 0;
|
||||
#if defined(STM32F7)
|
||||
uint32_t CR2 = 0;
|
||||
#if defined(STM32F7XX)
|
||||
if (t->dss == SPIDss16bit) {
|
||||
CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2 | SPI_CR2_DS_3;
|
||||
} else {
|
||||
CR2 |= SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2;
|
||||
}
|
||||
#endif /* STM32F7 */
|
||||
#endif /* STM32F7XX */
|
||||
#if defined(STM32H7XX)
|
||||
if (t->bitorder == SPILSBFirst) {
|
||||
CR2 |= SPI_CFG2_LSBFRST;
|
||||
}
|
||||
if (t->cpha == SPICphaEdge2) {
|
||||
CR2 |= SPI_CFG2_CPHA;
|
||||
}
|
||||
if (t->cpol == SPICpolIdleHigh) {
|
||||
CR2 |= SPI_CFG2_CPOL;
|
||||
}
|
||||
#endif /* STM32H7XX */
|
||||
return CR2;
|
||||
}
|
||||
|
||||
@@ -249,7 +304,7 @@ static void handle_spi_thd(struct spi_periph *p)
|
||||
struct spi_init *i = (struct spi_init *) p->init_struct;
|
||||
|
||||
// wait for a transaction to be pushed in the queue
|
||||
chSemWait(i->sem);
|
||||
chSemWait(&i->sem);
|
||||
|
||||
if ((p->trans_insert_idx == p->trans_extract_idx) || p->suspend) {
|
||||
p->status = SPIIdle;
|
||||
@@ -264,11 +319,15 @@ static void handle_spi_thd(struct spi_periph *p)
|
||||
|
||||
SPIConfig spi_cfg = {
|
||||
false, // no circular buffer
|
||||
#if defined(HAL_LLD_SELECT_SPI_V2)
|
||||
false, // no slave mode
|
||||
NULL, // no callback
|
||||
#endif
|
||||
NULL, // no callback
|
||||
spi_resolve_slave_port(t->slave_idx),
|
||||
spi_resolve_slave_pin(t->slave_idx),
|
||||
spi_resolve_CR1(t),
|
||||
spi_resolve_CR2(t)
|
||||
spi_resolve_CR2(t),
|
||||
};
|
||||
|
||||
// find max transaction length
|
||||
@@ -293,10 +352,12 @@ static void handle_spi_thd(struct spi_periph *p)
|
||||
}
|
||||
|
||||
// Start synchronous data transfer
|
||||
#if defined STM32F7
|
||||
// we do stupid mem copy because F7 needs a special RAM for DMA operation
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
// we do stupid mem copy because F7/H7 needs a special RAM for DMA operation
|
||||
memcpy(i->dma_buf_out, (void *)t->output_buf, (size_t)t->output_length);
|
||||
cacheBufferFlush(i->dma_buf_out, t->output_length);
|
||||
spiExchange((SPIDriver *)p->reg_addr, t_length, i->dma_buf_out, i->dma_buf_in);
|
||||
cacheBufferInvalidate(i->dma_buf_in, t->input_length);
|
||||
memcpy((void *)t->input_buf, i->dma_buf_in, (size_t)t->input_length);
|
||||
#else
|
||||
spiExchange((SPIDriver *)p->reg_addr, t_length, (uint8_t *)t->output_buf, (uint8_t *)t->input_buf);
|
||||
@@ -330,163 +391,99 @@ static void handle_spi_thd(struct spi_periph *p)
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Default spi thread
|
||||
*
|
||||
* @param arg The SPI perpheral (struct spi_periph)
|
||||
*/
|
||||
static __attribute__((noreturn)) void thd_spi(void *arg)
|
||||
{
|
||||
struct spi_periph *spip = (struct spi_periph *)arg;
|
||||
struct spi_init *init_s = (struct spi_init *)spip->init_struct;
|
||||
chRegSetThreadName(init_s->name);
|
||||
|
||||
while (TRUE) {
|
||||
handle_spi_thd(spip);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure SPI peripherals
|
||||
*/
|
||||
|
||||
#if USE_SPI1
|
||||
static SEMAPHORE_DECL(spi1_sem, 0);
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t spi1_dma_buf_out[SPI_DMA_BUF_LEN]);
|
||||
static IN_DMA_SECTION(uint8_t spi1_dma_buf_in[SPI_DMA_BUF_LEN]);
|
||||
static struct spi_init spi1_init_s = {
|
||||
.sem = &spi1_sem,
|
||||
.dma_buf_out = spi1_dma_buf_out,
|
||||
.dma_buf_in = spi1_dma_buf_in
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct spi_init spi1_init_s) = {
|
||||
.name = "spi1",
|
||||
.sem = __SEMAPHORE_DATA(spi1_init_s.sem, 0),
|
||||
};
|
||||
#else
|
||||
static struct spi_init spi1_init_s = {
|
||||
.sem = &spi1_sem,
|
||||
};
|
||||
#endif
|
||||
|
||||
static __attribute__((noreturn)) void thd_spi1(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("spi1");
|
||||
|
||||
while (TRUE) {
|
||||
handle_spi_thd(&spi1);
|
||||
}
|
||||
}
|
||||
|
||||
static THD_WORKING_AREA(wa_thd_spi1, SPI_THREAD_STACK_SIZE);
|
||||
|
||||
// Initialize the interface
|
||||
void spi1_arch_init(void)
|
||||
{
|
||||
spi1.reg_addr = &SPID1;
|
||||
spi1.init_struct = &spi1_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_spi1, sizeof(wa_thd_spi1),
|
||||
NORMALPRIO + 1, thd_spi1, NULL);
|
||||
NORMALPRIO + 1, thd_spi, (void *)&spi1);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if USE_SPI2
|
||||
static SEMAPHORE_DECL(spi2_sem, 0);
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t spi2_dma_buf_out[SPI_DMA_BUF_LEN]);
|
||||
static IN_DMA_SECTION(uint8_t spi2_dma_buf_in[SPI_DMA_BUF_LEN]);
|
||||
static struct spi_init spi2_init_s = {
|
||||
.sem = &spi2_sem,
|
||||
.dma_buf_out = spi2_dma_buf_out,
|
||||
.dma_buf_in = spi2_dma_buf_in
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct spi_init spi2_init_s) = {
|
||||
.name = "spi2",
|
||||
.sem = __SEMAPHORE_DATA(spi2_init_s.sem, 0),
|
||||
};
|
||||
#else
|
||||
static struct spi_init spi2_init_s = {
|
||||
.sem = &spi2_sem,
|
||||
};
|
||||
#endif
|
||||
|
||||
static __attribute__((noreturn)) void thd_spi2(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("spi2");
|
||||
|
||||
while (TRUE) {
|
||||
handle_spi_thd(&spi2);
|
||||
}
|
||||
}
|
||||
|
||||
static THD_WORKING_AREA(wa_thd_spi2, SPI_THREAD_STACK_SIZE);
|
||||
|
||||
// Initialize the interface
|
||||
void spi2_arch_init(void)
|
||||
{
|
||||
spi2.reg_addr = &SPID2;
|
||||
spi2.init_struct = &spi2_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_spi2, sizeof(wa_thd_spi2),
|
||||
NORMALPRIO + 1, thd_spi2, NULL);
|
||||
NORMALPRIO + 1, thd_spi, (void *)&spi2);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if USE_SPI3
|
||||
static SEMAPHORE_DECL(spi3_sem, 0);
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t spi3_dma_buf_out[SPI_DMA_BUF_LEN]);
|
||||
static IN_DMA_SECTION(uint8_t spi3_dma_buf_in[SPI_DMA_BUF_LEN]);
|
||||
static struct spi_init spi3_init_s = {
|
||||
.sem = &spi3_sem,
|
||||
.dma_buf_out = spi3_dma_buf_out,
|
||||
.dma_buf_in = spi3_dma_buf_in
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct spi_init spi3_init_s) = {
|
||||
.name = "spi3",
|
||||
.sem = __SEMAPHORE_DATA(spi3_init_s.sem, 0),
|
||||
};
|
||||
#else
|
||||
static struct spi_init spi3_init_s = {
|
||||
.sem = &spi3_sem,
|
||||
};
|
||||
#endif
|
||||
|
||||
static __attribute__((noreturn)) void thd_spi3(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("spi3");
|
||||
|
||||
while (TRUE) {
|
||||
handle_spi_thd(&spi3);
|
||||
}
|
||||
}
|
||||
|
||||
static THD_WORKING_AREA(wa_thd_spi3, SPI_THREAD_STACK_SIZE);
|
||||
|
||||
// Initialize the interface
|
||||
void spi3_arch_init(void)
|
||||
{
|
||||
spi3.reg_addr = &SPID3;
|
||||
spi3.init_struct = &spi3_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_spi3, sizeof(wa_thd_spi3),
|
||||
NORMALPRIO + 1, thd_spi3, NULL);
|
||||
NORMALPRIO + 1, thd_spi, (void *)&spi3);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if USE_SPI4
|
||||
static SEMAPHORE_DECL(spi4_sem, 0);
|
||||
#if defined STM32F7
|
||||
// We need a special buffer for DMA operations
|
||||
static IN_DMA_SECTION(uint8_t spi4_dma_buf_out[SPI_DMA_BUF_LEN]);
|
||||
static IN_DMA_SECTION(uint8_t spi4_dma_buf_in[SPI_DMA_BUF_LEN]);
|
||||
static struct spi_init spi4_init_s = {
|
||||
.sem = &spi4_sem,
|
||||
.dma_buf_out = spi4_dma_buf_out,
|
||||
.dma_buf_in = spi4_dma_buf_in
|
||||
// Local variables (in DMA safe memory)
|
||||
static IN_DMA_SECTION(struct spi_init spi4_init_s) = {
|
||||
.name = "spi4",
|
||||
.sem = __SEMAPHORE_DATA(spi4_init_s.sem, 0),
|
||||
};
|
||||
#else
|
||||
static struct spi_init spi4_init_s = {
|
||||
.sem = &spi4_sem,
|
||||
};
|
||||
#endif
|
||||
|
||||
static __attribute__((noreturn)) void thd_spi4(void *arg)
|
||||
{
|
||||
(void) arg;
|
||||
chRegSetThreadName("spi4");
|
||||
|
||||
while (TRUE) {
|
||||
handle_spi_thd(&spi4);
|
||||
}
|
||||
}
|
||||
|
||||
static THD_WORKING_AREA(wa_thd_spi4, SPI_THREAD_STACK_SIZE);
|
||||
|
||||
// Initialize the interface
|
||||
void spi4_arch_init(void)
|
||||
{
|
||||
spi4.reg_addr = &SPID4;
|
||||
spi4.init_struct = &spi4_init_s;
|
||||
// Create thread
|
||||
chThdCreateStatic(wa_thd_spi4, sizeof(wa_thd_spi4),
|
||||
NORMALPRIO + 1, thd_spi4, NULL);
|
||||
NORMALPRIO + 1, thd_spi, (void *)&spi4);
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -530,7 +527,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
|
||||
p->trans_insert_idx = idx;
|
||||
|
||||
chSysUnlock();
|
||||
chSemSignal(((struct spi_init *)p->init_struct)->sem);
|
||||
chSemSignal(&((struct spi_init *)p->init_struct)->sem);
|
||||
// transaction submitted
|
||||
return TRUE;
|
||||
}
|
||||
@@ -574,6 +571,21 @@ void spi_slave_select(uint8_t slave)
|
||||
gpio_clear(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE5
|
||||
#if USE_SPI_SLAVE6
|
||||
case 6:
|
||||
gpio_clear(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE6
|
||||
#if USE_SPI_SLAVE7
|
||||
case 7:
|
||||
gpio_clear(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE7
|
||||
#if USE_SPI_SLAVE8
|
||||
case 8:
|
||||
gpio_clear(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE8
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -616,6 +628,21 @@ void spi_slave_unselect(uint8_t slave)
|
||||
gpio_set(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE5
|
||||
#if USE_SPI_SLAVE6
|
||||
case 6:
|
||||
gpio_set(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE6
|
||||
#if USE_SPI_SLAVE7
|
||||
case 7:
|
||||
gpio_set(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE7
|
||||
#if USE_SPI_SLAVE8
|
||||
case 8:
|
||||
gpio_set(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN);
|
||||
break;
|
||||
#endif //USE_SPI_SLAVE8
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -685,5 +712,19 @@ void spi_init_slaves(void)
|
||||
gpio_setup_output(SPI_SELECT_SLAVE5_PORT, SPI_SELECT_SLAVE5_PIN);
|
||||
spi_slave_unselect(5);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if USE_SPI_SLAVE6
|
||||
gpio_setup_output(SPI_SELECT_SLAVE6_PORT, SPI_SELECT_SLAVE6_PIN);
|
||||
spi_slave_unselect(6);
|
||||
#endif
|
||||
|
||||
#if USE_SPI_SLAVE7
|
||||
gpio_setup_output(SPI_SELECT_SLAVE7_PORT, SPI_SELECT_SLAVE7_PIN);
|
||||
spi_slave_unselect(7);
|
||||
#endif
|
||||
|
||||
#if USE_SPI_SLAVE8
|
||||
gpio_setup_output(SPI_SELECT_SLAVE8_PORT, SPI_SELECT_SLAVE8_PIN);
|
||||
spi_slave_unselect(8);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -39,6 +39,10 @@
|
||||
|
||||
static MUTEX_DECL(sys_time_mtx);
|
||||
|
||||
#ifndef STM32_SYSCLK
|
||||
#define STM32_SYSCLK STM32_SYS_CK
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Sys_tick handler thread
|
||||
*/
|
||||
@@ -59,7 +63,7 @@ void sys_time_arch_init(void)
|
||||
|
||||
// Create thread (PRIO should be higher than AP threads
|
||||
chThdCreateStatic(wa_thd_sys_tick, sizeof(wa_thd_sys_tick),
|
||||
NORMALPRIO+2, thd_sys_tick, NULL);
|
||||
NORMALPRIO + 2, thd_sys_tick, NULL);
|
||||
|
||||
}
|
||||
|
||||
@@ -73,8 +77,8 @@ uint32_t get_sys_time_usec(void)
|
||||
chMtxLock(&sys_time_mtx);
|
||||
uint32_t current = chSysGetRealtimeCounterX();
|
||||
uint32_t t = sys_time.nb_sec * 1000000 +
|
||||
TIME_I2US(sys_time.nb_sec_rem) +
|
||||
RTC2US(STM32_SYSCLK, current - cpu_counter);
|
||||
TIME_I2US(sys_time.nb_sec_rem) +
|
||||
RTC2US(STM32_SYSCLK, current - cpu_counter);
|
||||
chMtxUnlock(&sys_time_mtx);
|
||||
return t;
|
||||
}
|
||||
@@ -84,8 +88,8 @@ uint32_t get_sys_time_msec(void)
|
||||
chMtxLock(&sys_time_mtx);
|
||||
uint32_t current = chSysGetRealtimeCounterX();
|
||||
uint32_t t = sys_time.nb_sec * 1000 +
|
||||
TIME_I2MS(sys_time.nb_sec_rem) +
|
||||
RTC2MS(STM32_SYSCLK, current - cpu_counter);
|
||||
TIME_I2MS(sys_time.nb_sec_rem) +
|
||||
RTC2MS(STM32_SYSCLK, current - cpu_counter);
|
||||
chMtxUnlock(&sys_time_mtx);
|
||||
return t;
|
||||
}
|
||||
@@ -131,7 +135,7 @@ static __attribute__((noreturn)) void thd_sys_tick(void *arg)
|
||||
while (TRUE) {
|
||||
systime_t t = chVTGetSystemTime();
|
||||
sys_tick_handler();
|
||||
chThdSleepUntilWindowed(t, t + TIME_US2I(USEC_OF_SEC(1.f/(SYS_TIME_FREQUENCY))));
|
||||
chThdSleepUntilWindowed(t, t + TIME_US2I(USEC_OF_SEC(1.f / (SYS_TIME_FREQUENCY))));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -998,13 +998,14 @@ void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud)
|
||||
*/
|
||||
void uart_periph_set_mode(struct uart_periph *p __attribute__((unused)), bool tx_enabled __attribute__((unused)),
|
||||
bool rx_enabled __attribute__((unused)), bool hw_flow_control __attribute__((unused))) {}
|
||||
|
||||
#if defined STM32F7
|
||||
#if defined(STM32H7XX)
|
||||
#define __USART_CR1_M USART_CR1_M0
|
||||
#elif defined(STM32F7XX)
|
||||
#define __USART_CR1_M USART_CR1_M_0
|
||||
#elif defined STM32F1 || defined STM32F4 || defined STM32F3
|
||||
#elif defined(STM32F1XX) || defined (STM32F3XX) || defined(STM32F4XX)
|
||||
#define __USART_CR1_M USART_CR1_M
|
||||
#else
|
||||
#error unsupported board
|
||||
#error Unsupported board
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -1049,7 +1050,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p,
|
||||
sdStart((SerialDriver *)(p->reg_addr), conf);
|
||||
}
|
||||
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7XX) || defined(STM32H7XX)
|
||||
/**
|
||||
* Invert data logic
|
||||
*/
|
||||
@@ -1159,4 +1160,3 @@ void uart_send_message(struct uart_periph *p, long fd)
|
||||
// send signal to start transmission
|
||||
chSemSignal(init_struct->tx_sem);
|
||||
}
|
||||
|
||||
|
||||
@@ -34,6 +34,48 @@
|
||||
#include "modules/actuators/actuators_pwm.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
|
||||
/* Default timer base frequency is 1MHz */
|
||||
#ifndef PWM_FREQUENCY
|
||||
#define PWM_FREQUENCY 1000000
|
||||
#endif
|
||||
|
||||
/* Default servo update rate in Hz */
|
||||
#ifndef SERVO_HZ
|
||||
#define SERVO_HZ 40
|
||||
#endif
|
||||
|
||||
/* For each timer the period van be configured differently */
|
||||
#ifndef TIM1_SERVO_HZ
|
||||
#define TIM1_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM2_SERVO_HZ
|
||||
#define TIM2_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM3_SERVO_HZ
|
||||
#define TIM3_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM4_SERVO_HZ
|
||||
#define TIM4_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM5_SERVO_HZ
|
||||
#define TIM5_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM8_SERVO_HZ
|
||||
#define TIM8_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM9_SERVO_HZ
|
||||
#define TIM9_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
#ifndef TIM12_SERVO_HZ
|
||||
#define TIM12_SERVO_HZ SERVO_HZ
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Print the configuration variables from the header
|
||||
*/
|
||||
PRINT_CONFIG_VAR(ACTUATORS_PWM_NB)
|
||||
PRINT_CONFIG_VAR(PWM_FREQUENCY)
|
||||
PRINT_CONFIG_VAR(SERVO_HZ)
|
||||
|
||||
/**
|
||||
* CMD_TO_US() is depending on architecture
|
||||
@@ -60,35 +102,165 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB];
|
||||
*/
|
||||
__attribute__((unused)) static void pwmpcb(PWMDriver *pwmp __attribute__((unused))) {}
|
||||
|
||||
#if PWM_CONF_TIM1
|
||||
static PWMConfig pwmcfg1 = PWM_CONF1_DEF;
|
||||
#if STM32_PWM_USE_TIM1
|
||||
static PWMConfig pwmcfg1 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM1_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM2
|
||||
static PWMConfig pwmcfg2 = PWM_CONF2_DEF;
|
||||
#if STM32_PWM_USE_TIM2
|
||||
static PWMConfig pwmcfg2 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM2_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM3
|
||||
static PWMConfig pwmcfg3 = PWM_CONF3_DEF;
|
||||
#if STM32_PWM_USE_TIM3
|
||||
static PWMConfig pwmcfg3 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM3_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM4
|
||||
static PWMConfig pwmcfg4 = PWM_CONF4_DEF;
|
||||
#if STM32_PWM_USE_TIM4
|
||||
static PWMConfig pwmcfg4 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM4_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM5
|
||||
static PWMConfig pwmcfg5 = PWM_CONF5_DEF;
|
||||
#if STM32_PWM_USE_TIM5
|
||||
static PWMConfig pwmcfg5 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM5_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM8
|
||||
static PWMConfig pwmcfg8 = PWM_CONF8_DEF;
|
||||
#if STM32_PWM_USE_TIM8
|
||||
static PWMConfig pwmcfg8 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM8_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM9
|
||||
static PWMConfig pwmcfg9 = PWM_CONF9_DEF;
|
||||
#if STM32_PWM_USE_TIM9
|
||||
static PWMConfig pwmcfg9 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM9_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM10
|
||||
static PWMConfig pwmcfg10 = PWM_CONF10_DEF;
|
||||
#if STM32_PWM_USE_TIM10
|
||||
static PWMConfig pwmcfg10 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM10_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM11
|
||||
static PWMConfig pwmcfg11 = PWM_CONF11_DEF;
|
||||
#if STM32_PWM_USE_TIM11
|
||||
static PWMConfig pwmcfg11 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM11_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
#if PWM_CONF_TIM12
|
||||
static PWMConfig pwmcfg12 = PWM_CONF12_DEF;
|
||||
#if STM32_PWM_USE_TIM12
|
||||
static PWMConfig pwmcfg12 = {
|
||||
.frequency = PWM_FREQUENCY,
|
||||
.period = PWM_FREQUENCY/TIM12_SERVO_HZ,
|
||||
.callback = NULL,
|
||||
.channels = {
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
{ PWM_OUTPUT_DISABLED, NULL },
|
||||
},
|
||||
.cr2 = 0,
|
||||
.bdtr = 0,
|
||||
.dier = 0
|
||||
};
|
||||
#endif
|
||||
|
||||
|
||||
@@ -99,87 +271,104 @@ void actuators_pwm_arch_init(void)
|
||||
*----------------*/
|
||||
#ifdef PWM_SERVO_0
|
||||
gpio_setup_pin_af(PWM_SERVO_0_GPIO, PWM_SERVO_0_PIN, PWM_SERVO_0_AF, true);
|
||||
PWM_SERVO_0_CONF.channels[PWM_SERVO_0_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_1
|
||||
gpio_setup_pin_af(PWM_SERVO_1_GPIO, PWM_SERVO_1_PIN, PWM_SERVO_1_AF, true);
|
||||
PWM_SERVO_1_CONF.channels[PWM_SERVO_1_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_2
|
||||
gpio_setup_pin_af(PWM_SERVO_2_GPIO, PWM_SERVO_2_PIN, PWM_SERVO_2_AF, true);
|
||||
PWM_SERVO_2_CONF.channels[PWM_SERVO_2_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_3
|
||||
gpio_setup_pin_af(PWM_SERVO_3_GPIO, PWM_SERVO_3_PIN, PWM_SERVO_3_AF, true);
|
||||
PWM_SERVO_3_CONF.channels[PWM_SERVO_3_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_4
|
||||
gpio_setup_pin_af(PWM_SERVO_4_GPIO, PWM_SERVO_4_PIN, PWM_SERVO_4_AF, true);
|
||||
PWM_SERVO_4_CONF.channels[PWM_SERVO_4_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_5
|
||||
gpio_setup_pin_af(PWM_SERVO_5_GPIO, PWM_SERVO_5_PIN, PWM_SERVO_5_AF, true);
|
||||
PWM_SERVO_5_CONF.channels[PWM_SERVO_5_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_6
|
||||
gpio_setup_pin_af(PWM_SERVO_6_GPIO, PWM_SERVO_6_PIN, PWM_SERVO_6_AF, true);
|
||||
PWM_SERVO_6_CONF.channels[PWM_SERVO_6_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_7
|
||||
gpio_setup_pin_af(PWM_SERVO_7_GPIO, PWM_SERVO_7_PIN, PWM_SERVO_7_AF, true);
|
||||
PWM_SERVO_7_CONF.channels[PWM_SERVO_7_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_8
|
||||
gpio_setup_pin_af(PWM_SERVO_8_GPIO, PWM_SERVO_8_PIN, PWM_SERVO_8_AF, true);
|
||||
PWM_SERVO_8_CONF.channels[PWM_SERVO_8_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_9
|
||||
gpio_setup_pin_af(PWM_SERVO_9_GPIO, PWM_SERVO_9_PIN, PWM_SERVO_9_AF, true);
|
||||
PWM_SERVO_9_CONF.channels[PWM_SERVO_9_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_10
|
||||
gpio_setup_pin_af(PWM_SERVO_10_GPIO, PWM_SERVO_10_PIN, PWM_SERVO_10_AF, true);
|
||||
PWM_SERVO_10_CONF.channels[PWM_SERVO_10_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_11
|
||||
gpio_setup_pin_af(PWM_SERVO_11_GPIO, PWM_SERVO_11_PIN, PWM_SERVO_11_AF, true);
|
||||
PWM_SERVO_11_CONF.channels[PWM_SERVO_11_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_12
|
||||
gpio_setup_pin_af(PWM_SERVO_12_GPIO, PWM_SERVO_12_PIN, PWM_SERVO_12_AF, true);
|
||||
PWM_SERVO_12_CONF.channels[PWM_SERVO_12_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_13
|
||||
gpio_setup_pin_af(PWM_SERVO_13_GPIO, PWM_SERVO_13_PIN, PWM_SERVO_13_AF, true);
|
||||
PWM_SERVO_13_CONF.channels[PWM_SERVO_13_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_14
|
||||
gpio_setup_pin_af(PWM_SERVO_14_GPIO, PWM_SERVO_14_PIN, PWM_SERVO_14_AF, true);
|
||||
PWM_SERVO_14_CONF.channels[PWM_SERVO_14_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_15
|
||||
gpio_setup_pin_af(PWM_SERVO_15_GPIO, PWM_SERVO_15_PIN, PWM_SERVO_15_AF, true);
|
||||
PWM_SERVO_15_CONF.channels[PWM_SERVO_15_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
#ifdef PWM_SERVO_16
|
||||
gpio_setup_pin_af(PWM_SERVO_16_GPIO, PWM_SERVO_16_PIN, PWM_SERVO_16_AF, true);
|
||||
PWM_SERVO_16_CONF.channels[PWM_SERVO_16_CHANNEL].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
||||
#endif
|
||||
|
||||
/*---------------
|
||||
* Configure PWM
|
||||
*---------------*/
|
||||
#if PWM_CONF_TIM1
|
||||
#if STM32_PWM_USE_TIM1
|
||||
pwmStart(&PWMD1, &pwmcfg1);
|
||||
#endif
|
||||
#if PWM_CONF_TIM2
|
||||
#if STM32_PWM_USE_TIM2
|
||||
pwmStart(&PWMD2, &pwmcfg2);
|
||||
#endif
|
||||
#if PWM_CONF_TIM3
|
||||
#if STM32_PWM_USE_TIM3
|
||||
pwmStart(&PWMD3, &pwmcfg3);
|
||||
#endif
|
||||
#if PWM_CONF_TIM4
|
||||
#if STM32_PWM_USE_TIM4
|
||||
pwmStart(&PWMD4, &pwmcfg4);
|
||||
#endif
|
||||
#if PWM_CONF_TIM5
|
||||
#if STM32_PWM_USE_TIM5
|
||||
pwmStart(&PWMD5, &pwmcfg5);
|
||||
#endif
|
||||
#if PWM_CONF_TIM8
|
||||
#if STM32_PWM_USE_TIM8
|
||||
pwmStart(&PWMD8, &pwmcfg8);
|
||||
#endif
|
||||
#if PWM_CONF_TIM9
|
||||
#if STM32_PWM_USE_TIM9
|
||||
pwmStart(&PWMD9, &pwmcfg9);
|
||||
#endif
|
||||
#if PWM_CONF_TIM10
|
||||
#if STM32_PWM_USE_TIM10
|
||||
pwmStart(&PWMD10, &pwmcfg10);
|
||||
#endif
|
||||
#if PWM_CONF_TIM11
|
||||
#if STM32_PWM_USE_TIM11
|
||||
pwmStart(&PWMD11, &pwmcfg11);
|
||||
#endif
|
||||
#if PWM_CONF_TIM12
|
||||
#if STM32_PWM_USE_TIM12
|
||||
pwmStart(&PWMD12, &pwmcfg12);
|
||||
#endif
|
||||
}
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user