[chibios] Update and add Pixhawk 6X autopilot (#3254)

* [chibios] Update chibios and add Pixhawk 6X autopilot

* [conf] Change rotating wing 25kg

* [modules] Fix chibios sdlogger dependency on ADC

* [modules] Fix eff scheduling rotating wing warnings

* [chibios] Cleanup and fixes
This commit is contained in:
Freek van Tienen
2024-05-24 15:35:04 +02:00
committed by GitHub
parent 5e9e61e499
commit 2a9887a747
47 changed files with 3201 additions and 206 deletions

View File

@@ -0,0 +1,360 @@
<!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="pixhawk_6x">
<configure name="PERIODIC_FREQUENCY" value="500"/>
<define name="SYS_TIME_FREQUENCY" value="1500"/><!-- To be able to send 3x IMU measurements -->
<configure name="TELEMETRY_FREQUENCY" value="1500"/><!-- To be able to send 3x IMU measurements -->
<!--configure name="RTOS_DEBUG" value="1"/-->
<module name="radio_control" type="sbus"/>
<define name="USE_I2C2"/>
<module name="airspeed" type="ms45xx_i2c">
<define name="MS45XX_I2C_DEV" value="i2c2"/>
<define name="MS45XX_PRESSURE_SCALE" value="1.9077609"/>
<define name="USE_AIRSPEED_LOWPASS_FILTER" value="TRUE"/>
<define name="MS45XX_LOWPASS_TAU" value="0.15"/>
<define name="AIRSPEED_MS45XX_SEND_ABI" value="1"/>
</module>
<module name="airspeed" type="uavcan">
<define name="AIRSPEED_UAVCAN_LOWPASS_FILTER" value="TRUE" />
<define name="AIRSPEED_UAVCAN_LOWPASS_PERIOD" value="0.1" />
<define name="AIRSPEED_UAVCAN_LOWPASS_TAU" value="0.15" />
<define name="AIRSPEED_UAVCAN_SEND_ABI" value="0" /> <!-- Read Airspeed for logging but do not use it -->
</module>
<module name="range_sensor" type="uavcan"/>
<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"/>
<!-- Choose which sensors to use in the EKF2 (not in NPS target as then it needs to listen to all) -->
<define name="INS_EKF2_ACCEL_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_GYRO_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_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="LOGGER_FILE_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="preflight_checks"/>
<module name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B115200"/>
<configure name="MODEM_PORT" value="usb_serial"/>
</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="pixhawk6x"/>
<module name="gps" type="ublox"/>
<module name="stabilization" type="indi_simple"/>
<module name="stabilization" type="rate_indi"/>
<module name="ins" type="ekf2"/>
<module name="nav" type="hybrid"/>
<module name="air_data"/>
<!-- 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" type="rm3100">
<define name="MODULE_RM3100_UPDATE_AHRS" value="TRUE"/>
<configure name="MAG_RM3100_I2C_DEV" value="I2C1"/>
</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_tailsitter">
<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_LIFTD_ASQ" value="0.20"/>
<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_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"/>
<define name="GUIDANCE_INDI_THRUST_DYNAMICS_FREQ" value="18"/>
</module>
<module name="motor_mixing"/>
</firmware>
<!-- CPWM outputs -->
<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 outputs -->
<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>
<!-- CAN BUS 2 outputs -->
<servos driver="Uavcan2">
<servo name="MOTOR_8" no="0" min="-8191" neutral="1500" max="8191"/>
<servo name="MOTOR_9" no="1" min="-8191" neutral="1500" max="8191"/>
<servo name="MOTOR_10" no="2" min="-8191" neutral="1500" max="8191"/>
<servo name="MOTOR_11" no="3" min="-8191" neutral="1500" max="8191"/>
<servo name="MOTOR_12" no="4" min="-8191" neutral="1500" max="8191"/>
</servos>
<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan1Cmd">
<servo name="AIL_3" no="6" min="6000" neutral="0" max="-6000"/>
<servo name="FLAP_3" no="7" min="6000" neutral="0" max="-6000"/>
</servos>
<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan2Cmd">
<servo name="FLAP_4" no="8" min="-6000" neutral="0" max="6000"/>
<servo name="AIL_4" 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])"/>
<set servo="MOTOR_7" value="($th_hold? -9600 : motor_mixing.commands[6])"/>
<set servo="MOTOR_8" value="($th_hold? -9600 : motor_mixing.commands[7])"/>
<set servo="MOTOR_9" value="($th_hold? -9600 : motor_mixing.commands[8])"/>
<set servo="MOTOR_10" value="($th_hold? -9600 : motor_mixing.commands[9])"/>
<set servo="MOTOR_11" value="($th_hold? -9600 : motor_mixing.commands[10])"/>
<set servo="MOTOR_12" value="($th_hold? -9600 : motor_mixing.commands[11])"/>
</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_">
<!-- Calibrations -->
<define name="MAG_CALIB" value="{{.abi_id=5, .calibrated={.neutral=true, .scale=true, .rotation=true},.neutral={-14,3,42}, .scale={{17279,2209,36874},{30247,3800,64095}}, .body_to_sensor={{0,16384,0,-16384,0,0,0,0,16384}}}}"/>
<!-- Define axis in hover frame -->
<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="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_FREQ_P" value="18"/>
<define name="ACT_FREQ_Q" value="18"/>
<define name="ACT_FREQ_R" value="18"/>
<!-- 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"/>
<!-- 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>

View File

@@ -10,12 +10,10 @@
<description>RotatingWing25Kg</description>
<firmware name="rotorcraft">
<target name="ap" board="cube_orangeplus">
<target name="ap" board="pixhawk_6x">
<configure name="PERIODIC_FREQUENCY" value="500"/> <!-- Configure the main periodic frequency to 500Hz -->
<module name="radio_control" type="sbus">
<configure name="SBUS_PORT" value="UART3"/> <!-- On the TELEM2 port -->
</module>
<module name="radio_control" type="sbus"/>
<module name="sys_mon"/>
<module name="flight_recorder"/>
@@ -27,23 +25,24 @@
<define name="RADIO_CONTROL_THRUST_X" value="RADIO_AUX4"/>
<!-- EKF2 configure inputs -->
<define name="INS_EKF2_GYRO_ID" value="IMU_CUBE1_ID"/>
<define name="INS_EKF2_ACCEL_ID" value="IMU_CUBE1_ID"/>
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_SENDER_ID"/>
<define name="INS_EKF2_GYRO_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_ACCEL_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_SENDER_ID"/>
<!--Only send gyro and accel that is being used-->
<define name="IMU_GYRO_ABI_SEND_ID" value= "IMU_CUBE1_ID"/>
<define name="IMU_ACCEL_ABI_SEND_ID" value= "IMU_CUBE1_ID"/>
<define name="IMU_GYRO_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>
<define name="IMU_ACCEL_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>
<!-- Range sensor connected to supercan -->
<module name="range_sensor_uavcan"/>
<!-- Disable current sensing using UAVCAN -->
<define name="UAVCAN_ACTUATORS_USE_CURRENT" value="FALSE"/>
<define name="USE_I2C1"/>
<define name="UAVCAN_ACTUATORS_USE_CURRENT" value="FALSE"/>
<!-- Log in high speed (Remove for outdoor flights) -->
<!-- <define name="IMU_LOG_HIGHSPEED" value="TRUE"/> -->
<define name="SERVO_ROTATION_MECH_IDX" value="0"/> <!-- !!!!!!!!!!!!!!!!!!!!!!!!!!!! FIXMEEE !!!!!!!!!!!!!!!!!!!!!!!!!! -->
</target>
<target name="nps" board="pc">
@@ -62,16 +61,17 @@
<!-- Herelink datalink -->
<module name="telemetry" type="transparent">
<configure name="MODEM_PORT" value="usb_serial"/>
<configure name="MODEM_BAUD" value="B460800"/>
</module>
<!-- Sensors -->
<module name="mag" type="rm3100">
<configure name="MAG_RM3100_I2C_DEV" value="I2C1"/>
<define name="MODULE_RM3100_UPDATE_AHRS" value="TRUE"/>
<configure name="MAG_RM3100_I2C_DEV" value="I2C2"/>
</module>
<module name="airspeed" type="ms45xx_i2c">
<define name="MS45XX_I2C_DEV" value="i2c1"/>
<configure name="MS45XX_I2C_DEV" value="I2C2"/>
<define name="MS45XX_AIRSPEED_SCALE" value="2.0833"/>
<define name="USE_AIRSPEED_LOWPASS_FILTER" value="TRUE"/>
<define name="MS45XX_LOWPASS_TAU" value="0.15"/>
@@ -88,7 +88,7 @@
</module>
<!-- IMU / INS -->
<module name="imu" type="cube"/>
<module name="imu" type="pixhawk6x"/>
<module name="ins" type="ekf2">
<!-- The Cube is mounted 25cm backwards of the CG -->
<define name="INS_EKF2_IMU_POS_X" value="-0.25"/>
@@ -141,36 +141,42 @@
<!-- Can bus 1 actuators -->
<servos driver="Uavcan1">
<servo no="0" name="MOTOR_FRONT" min="-8191" neutral="-5000" max="8191"/>
<servo no="1" name="MOTOR_RIGHT" min="-8191" neutral="-5000" max="8191"/>
<servo no="2" name="MOTOR_BACK" min="-8191" neutral="-5000" max="8191"/>
<servo no="3" name="MOTOR_LEFT" min="-8191" neutral="-5000" max="8191"/>
<servo no="4" name="MOTOR_PUSH" min="-8191" neutral="-8191" max="8191"/>
<servo no="5" name="SERVO_ELEVATOR" min="-3191" neutral="-3191" max="4900"/>
<servo no="6" name="SERVO_RUDDER" min="-6500" neutral="0" max="6500"/>
<servo no="7" name="ROTATION_MECH" min="8191" neutral="0" max="-8191"/>
<servo no="8" name="AIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="0" name="MOTOR_FRONT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="1" name="MOTOR_RIGHT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="2" name="MOTOR_BACK" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="3" name="MOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC is neutral -->
<servo no="4" name="MOTOR_PUSH" min="-3276" neutral="-3276" max="3605"/> <!-- Supercan (1100-1940us) -->
<!--servo no="8" name="AIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="9" name="FLAP_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="10" name="AIL_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="11" name="FLAP_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="12" name="PARACHUTE" min="-8191" neutral="0" max="8191"/>
<servo no="12" name="PARACHUTE" min="-8191" neutral="0" max="8191"/-->
</servos>
<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan1Cmd">
<servo no="5" name="SERVO_ELEVATOR" min="-3250" neutral="0" max="3250"/>
<servo no="6" name="SERVO_RUDDER" min="-3250" neutral="0" max="3250"/>
</servos>
<!-- Can bus 2 actuators -->
<servos driver="Uavcan2">
<servo no="0" name="BMOTOR_FRONT" min="-8191" neutral="-5000" max="8191"/>
<servo no="1" name="BMOTOR_RIGHT" min="-8191" neutral="-5000" max="8191"/>
<servo no="2" name="BMOTOR_BACK" min="-8191" neutral="-5000" max="8191"/>
<servo no="3" name="BMOTOR_LEFT" min="-8191" neutral="-5000" max="8191"/>
<servo no="4" name="BMOTOR_PUSH" min="-8191" neutral="-8191" max="8191"/>
<servo no="5" name="BSERVO_ELEVATOR" min="-3191" neutral="-3191" max="4900"/>
<servo no="6" name="BSERVO_RUDDER" min="-6500" neutral="0" max="6500"/>
<servo no="7" name="BROTATION_MECH" min="8191" neutral="0" max="-8191"/>
<servo no="8" name="BAIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="0" name="BMOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="1" name="BMOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="2" name="BMOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="3" name="BMOTOR_LEFT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="4" name="BMOTOR_PUSH" min="-3276" neutral="-3276" max="3605"/> <!-- Supercan (1100-1940us) -->
<!--servo no="8" name="BAIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="9" name="BFLAP_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="10" name="BAIL_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="11" name="BFLAP_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="12" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/>
<servo no="12" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/-->
</servos>
<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan2Cmd">
<servo no="5" name="BSERVO_ELEVATOR" min="-3250" neutral="0" max="3250"/>
<servo no="6" name="BSERVO_RUDDER" min="-3250" neutral="0" max="3250"/>
</servos>
<commands>
@@ -196,12 +202,12 @@
<set servo="MOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
<set servo="SERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
<set servo="SERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
<set servo="ROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<!--set servo="ROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<set servo="AIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="FLAP_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="AIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="FLAP_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="PARACHUTE" value="RadioControlValues(RADIO_AUX6)"/>
<set servo="PARACHUTE" value="RadioControlValues(RADIO_AUX6)"/-->
<!-- Second bus -->
<set servo="BMOTOR_FRONT" value="($hover_off? -9600 : actuators_pprz[0])"/>
@@ -211,12 +217,12 @@
<set servo="BMOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
<set servo="BSERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
<set servo="BSERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
<set servo="BROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<!--set servo="BROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<set servo="BAIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="BFLAP_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="BAIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="BFLAP_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="BPARACHUTE" value="RadioControlValues(RADIO_AUX6)"/>
<set servo="BPARACHUTE" value="RadioControlValues(RADIO_AUX6)"/-->
</command_laws>

View File

@@ -0,0 +1,92 @@
# 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=px4fmu
BOARD_VERSION=v6x
BOARD_DIR=$(BOARD)/chibios/$(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/px4fmu_v6x.prototype"
PX4_BL_PORT ?= "/dev/serial/by-id/*-BL_*,/dev/serial/by-id/*_BL_*"
#
# default LED configuration
#
SDLOG_LED ?= none
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= none
GPS_LED ?= none
SYS_TIME_LED ?= 4
#
# default UART configuration (modem, gps, spektrum)
# The TELEM2 port
SBUS_PORT ?= UART6
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART6
# The TELEM1 port (UART5 is TELEM2, UART2 is TELEM3)
MODEM_PORT ?= UART7
MODEM_BAUD ?= B57600
# The GPS1 port
GPS_PORT ?= UART1
GPS_BAUD ?= B460800
# The GPS2 port
GPS2_PORT ?= UART8
GPS2_BAUD ?= B460800
# InterMCU port connected to the IO processor
#INTERMCU_PORT ?= UART6
#INTERMCU_BAUD ?= B1500000
#
# 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

View File

@@ -7,7 +7,7 @@
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/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
settings_modules="modules/air_data.xml modules/airspeed_uavcan.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
/>
<aircraft
@@ -109,4 +109,15 @@
settings_modules="modules/air_data.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="red"
/>
<aircraft
name="Pixhawk6X"
ac_id="5"
airframe="airframes/examples/pixhawk_6x.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/airspeed_uavcan.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
/>
</conf>

View File

@@ -44,6 +44,10 @@
<event fun="ms45xx_i2c_event()"/>
<makefile target="ap">
<configure name="MS45XX_I2C_DEV" default="i2c2" case="lower|upper"/>
<define name="MS45XX_I2C_DEV" value="$(MS45XX_I2C_DEV_LOWER)"/>
<define name="USE_$(MS45XX_I2C_DEV_UPPER)"/>
<file name="airspeed_ms45xx_i2c.c"/>
<test>
<define name="MS45XX_I2C_PERIODIC_PERIOD" value="0.001"/>

View File

@@ -152,27 +152,39 @@ LIA_BARO ?= BARO_MS5611_SPI
# PX4FMU
else ifeq ($(BOARD),$(filter $(BOARD),px4fmu))
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
ifeq ($(BOARD_VERSION), 1.7)
# PX4FMU 1.7
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi1
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 2.4)
# PX4FMU 2.4 a.k.a. PIXHAWK
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi1
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 4.0)
# PX4FMU 4.0 a.k.a. PX4_PIXRACER
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi2
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 5.0)
# PX4FMU 5.0
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI4 -DUSE_SPI_SLAVE4
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi4
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE4

View File

@@ -0,0 +1,25 @@
<!DOCTYPE module SYSTEM "../module.dtd">
<module name="pixhawk_v6x" dir="boards">
<doc>
<description>
Specific configuration for Pixhawk V6X with ChibiOS
</description>
</doc>
<dep>
<depends>spi_master,baro_bmp3</depends>
</dep>
<makefile target="!sim|nps|fbw">
<define name="USE_RTC_BACKUP" value="TRUE"/>
<configure name="SDLOG_USE_RTC" value="FALSE"/>
<configure name="SDLOG_SDIO" value="SDCD2"/>
<!-- On FMU board -->
<!--configure name="BMP3_I2C_DEV" value="i2c2"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR"/-->
<!-- On IMU board -->
<configure name="BMP3_I2C_DEV" value="i2c4"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR_ALT"/>
</makefile>
</module>

View File

@@ -10,7 +10,7 @@
</description>
</doc>
<dep>
<depends>spi_master,imu_common,intermcu_iomcu,imu_heater</depends>
<depends>spi_master,i2c,imu_common,intermcu_iomcu,imu_heater</depends>
<provides>imu</provides>
</dep>
<header>

View File

@@ -0,0 +1,76 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="imu_pixhawk6x" dir="imu" task="sensors">
<doc>
<description>
IMU driver for the sensors inside the Pixhawk 6X autopilots
- IMU1: ICM42670
- IMU2: ???
- IMU3: ???
</description>
</doc>
<dep>
<depends>spi_master,i2c,imu_common,imu_heater</depends>
<provides>imu</provides>
</dep>
<header>
<file name="imu_pixhawk6x.h"/>
</header>
<init fun="imu_pixhawk6x_init()"/>
<periodic fun="imu_pixhawk6x_periodic()"/>
<event fun="imu_pixhawk6x_event()"/>
<makefile target="!sim|nps|fbw">
<!-- Files -->
<file name="invensense2.c" dir="peripherals"/>
<file name="invensense3.c" dir="peripherals"/>
<file name="imu_pixhawk6x.c"/>
<!-- IMU1: ICM42670 -->
<configure name="PIXHAWK6X_IMU1_SPI_DEV" default="spi1" case="lower|upper"/>
<configure name="PIXHAWK6X_IMU1_SPI_SLAVE_IDX" default="SPI_SLAVE1"/>
<define name="PIXHAWK6X_IMU1_SPI_DEV" value="$(PIXHAWK6X_IMU1_SPI_DEV_LOWER)"/>
<define name="USE_$(PIXHAWK6X_IMU1_SPI_DEV_UPPER)"/>
<define name="PIXHAWK6X_IMU1_SPI_SLAVE_IDX" value="$(PIXHAWK6X_IMU1_SPI_SLAVE_IDX)"/>
<define name="USE_$(PIXHAWK6X_IMU1_SPI_SLAVE_IDX)"/>
<!-- IMU2: ICM42688-->
<configure name="PIXHAWK6X_IMU2_SPI_DEV" default="spi2" case="lower|upper"/>
<configure name="PIXHAWK6X_IMU2_SPI_SLAVE_IDX" default="SPI_SLAVE2"/>
<define name="PIXHAWK6X_IMU2_SPI_DEV" value="$(PIXHAWK6X_IMU2_SPI_DEV_LOWER)"/>
<define name="USE_$(PIXHAWK6X_IMU2_SPI_DEV_UPPER)"/>
<define name="PIXHAWK6X_IMU2_SPI_SLAVE_IDX" value="$(PIXHAWK6X_IMU2_SPI_SLAVE_IDX)"/>
<define name="USE_$(PIXHAWK6X_IMU2_SPI_SLAVE_IDX)"/>
<!-- IMU3: BMI088 / ICM20649 -->
<configure name="PIXHAWK6X_IMU3_SPI_DEV" default="spi3" case="lower|upper"/>
<configure name="PIXHAWK6X_IMU3_SPI_SLAVE_IDX" default="SPI_SLAVE3"/>
<define name="PIXHAWK6X_IMU3_SPI_DEV" value="$(PIXHAWK6X_IMU3_SPI_DEV_LOWER)"/>
<define name="USE_$(PIXHAWK6X_IMU3_SPI_DEV_UPPER)"/>
<define name="PIXHAWK6X_IMU3_SPI_SLAVE_IDX" value="$(PIXHAWK6X_IMU3_SPI_SLAVE_IDX)"/>
<define name="USE_$(PIXHAWK6X_IMU3_SPI_SLAVE_IDX)"/>
<!-- Configure the heater (ICM42688) -->
<define name="IMU_HEATER_GYRO_ID" value="IMU_PIXHAWK2_ID"/>
<define name="IMU_HEATER_TARGET_TEMP" value="45.0"/>
<define name="IMU_HEATER_P_GAIN" value="50.0"/>
<define name="IMU_HEATER_I_GAIN" value="0.07"/>
<test>
<define name="SPI_MASTER"/>
<define name="PIXHAWK6X_IMU1_SPI_DEV" value="spi1"/>
<define name="PIXHAWK6X_IMU1_SPI_SLAVE_IDX" value="1"/>
<define name="PIXHAWK6X_IMU2_SPI_DEV" value="spi2"/>
<define name="PIXHAWK6X_IMU2_SPI_SLAVE_IDX" value="2"/>
<define name="PIXHAWK6X_IMU3_SPI_DEV" value="spi3"/>
<define name="PIXHAWK6X_IMU3_SPI_SLAVE_IDX" value="3"/>
<define name="USE_SPI1"/>
<define name="USE_SPI2"/>
<define name="USE_SPI3"/>
<define name="USE_SPI_SLAVE1"/>
<define name="USE_SPI_SLAVE2"/>
<define name="USE_SPI_SLAVE3"/>
<define name="PERIODIC_FREQUENCY" value="512"/>
<define name="IMU_PIXHAWK6X_PERIODIC_FREQ" value="512"/>
</test>
</makefile>
</module>

View File

@@ -9,6 +9,7 @@
Files are written on a FAT file system using the FatFS library and can be accessed
by using the autopilot as a mass storage (plug USB while the board is running).
</description>
<configure name="SDLOG_SDIO" value="SDCDx" description="The SDC device which the SD card is connected to. Default: SDCD1"/>
<configure name="SDLOG_LED" value="none|num" description="LED number or 'none' to disable. Default: none"/>
<define name="SDLOG_START_DELAY" value="30" unit="s" description="Set the delay in seconds before starting the logger. This delay can be used to get plug USB cable and get data without starting a new log. Default: 30s"/>
<define name="SDLOG_AUTO_FLUSH_PERIOD" value="10" unit="s" description="Data flush period. Shorter period may decrease performances. Default: 10s"/>
@@ -31,8 +32,17 @@
<init fun="sdlog_chibios_init()"/>
<datalink message="INFO_MSG_UP" fun="logger_log_msg_up(buf)"/>
<makefile target="ap">
<!-- LED -->
<configure name="SDLOG_LED" default="none"/>
<define name="SDLOG_LED" value="$(SDLOG_LED)" cond="ifneq ($(SDLOG_LED),none)"/>
<!-- SDMMC device -->
<configure name="SDLOG_SDIO" default="SDCD1" case="upper"/>
<define name="SDLOG_SDIO" value="$(SDLOG_SDIO_UPPER)"/>
<define name="FATFS_HAL_DEVICE" value="$(SDLOG_SDIO_UPPER)"/>
<define name="USE_$(SDLOG_SDIO_UPPER)"/>
<!-- Files -->
<file name="sdlog_chibios.c"/>
<file name="sdlog_chibios/sdLog.c"/>
<file name="sdlog_chibios/msg_queue.c"/>
@@ -41,6 +51,8 @@
<file name="sdlog_chibios/usb_msd.c"/>
<file name="sdlog_chibios/usbStorage.c"/>
<file_arch name="sdio_arch.c" dir="mcu_periph"/>
<!-- Configuration -->
<configure name="SDLOG_USE_RTC" default="TRUE"/>
<configure name="USE_FATFS" value="TRUE"/>
<define name="HAL_USE_RTC" value="TRUE" cond="ifeq (,$(findstring $(SDLOG_USE_RTC),0 FALSE))"/>

View File

@@ -593,37 +593,4 @@
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/parachute.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rot_wing_automation.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
gui_color="red"
/>
<aircraft
name="RotatingWingV3F"
ac_id="10"
airframe="airframes/tudelft/rot_wing_v3f.xml"
radio="radios/crossfire_sbus.xml"
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotating_wing_EHVB.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rot_wing_automation.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
gui_color="red"
/>
<aircraft
name="RotatingWingV3G"
ac_id="11"
airframe="airframes/tudelft/rot_wing_v3g.xml"
radio="radios/crossfire_sbus.xml"
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotating_wing_EHVB.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rot_wing_automation.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
gui_color="red"
/>
<aircraft
name="RotatingWingV3H"
ac_id="33"
airframe="airframes/tudelft/rot_wing_v3h.xml"
radio="radios/crossfire_sbus.xml"
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotating_wing_EHVB.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rot_wing_automation.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
gui_color="red"
/>
</conf>

View File

@@ -260,6 +260,11 @@ void __early_init(void)
{
stm32_gpio_init();
stm32_clock_init();
#if defined(STM32H7XX)
SCB->ITCMCR |= 1; // ITCM enable
SCB->DTCMCR |= 1; // DTCM enable
#endif
}
#if HAL_USE_SDC || defined(__DOXYGEN__)

View File

@@ -49,6 +49,14 @@
#define LED_1_GPIO_PIN PAL_PAD(LINE_LED1)
#define LED_1_GPIO_ON gpio_clear
#define LED_1_GPIO_OFF gpio_set
#elif defined(LINE_NLED1)
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO PAL_PORT(LINE_NLED1)
#define LED_1_GPIO_PIN PAL_PAD(LINE_NLED1)
#define LED_1_GPIO_ON gpio_set
#define LED_1_GPIO_OFF gpio_clear
#endif
#if defined(LINE_LED2)
@@ -59,6 +67,14 @@
#define LED_2_GPIO_PIN PAL_PAD(LINE_LED2)
#define LED_2_GPIO_ON gpio_clear
#define LED_2_GPIO_OFF gpio_set
#elif defined(LINE_NLED2)
#ifndef USE_LED_2
#define USE_LED_2 1
#endif
#define LED_2_GPIO PAL_PORT(LINE_NLED2)
#define LED_2_GPIO_PIN PAL_PAD(LINE_NLED2)
#define LED_2_GPIO_ON gpio_set
#define LED_2_GPIO_OFF gpio_clear
#endif
#if defined(LINE_LED3)
@@ -69,6 +85,14 @@
#define LED_3_GPIO_PIN PAL_PAD(LINE_LED3)
#define LED_3_GPIO_ON gpio_clear
#define LED_3_GPIO_OFF gpio_set
#elif defined(LINE_NLED3)
#ifndef USE_LED_3
#define USE_LED_3 1
#endif
#define LED_3_GPIO PAL_PORT(LINE_NLED3)
#define LED_3_GPIO_PIN PAL_PAD(LINE_NLED3)
#define LED_3_GPIO_ON gpio_set
#define LED_3_GPIO_OFF gpio_clear
#endif
#if defined(LINE_LED4)
@@ -79,6 +103,50 @@
#define LED_4_GPIO_PIN PAL_PAD(LINE_LED4)
#define LED_4_GPIO_ON gpio_clear
#define LED_4_GPIO_OFF gpio_set
#elif defined(LINE_NLED4)
#ifndef USE_LED_4
#define USE_LED_4 1
#endif
#define LED_4_GPIO PAL_PORT(LINE_NLED4)
#define LED_4_GPIO_PIN PAL_PAD(LINE_NLED4)
#define LED_4_GPIO_ON gpio_set
#define LED_4_GPIO_OFF gpio_clear
#endif
#if defined(LINE_LED5)
#ifndef USE_LED_5
#define USE_LED_5 1
#endif
#define LED_5_GPIO PAL_PORT(LINE_LED5)
#define LED_5_GPIO_PIN PAL_PAD(LINE_LED5)
#define LED_5_GPIO_ON gpio_clear
#define LED_5_GPIO_OFF gpio_set
#elif defined(LINE_NLED5)
#ifndef USE_LED_5
#define USE_LED_5 1
#endif
#define LED_5_GPIO PAL_PORT(LINE_NLED5)
#define LED_5_GPIO_PIN PAL_PAD(LINE_NLED5)
#define LED_5_GPIO_ON gpio_set
#define LED_5_GPIO_OFF gpio_clear
#endif
#if defined(LINE_LED6)
#ifndef USE_LED_6
#define USE_LED_6 1
#endif
#define LED_6_GPIO PAL_PORT(LINE_LED6)
#define LED_6_GPIO_PIN PAL_PAD(LINE_LED6)
#define LED_6_GPIO_ON gpio_clear
#define LED_6_GPIO_OFF gpio_set
#elif defined(LINE_NLED6)
#ifndef USE_LED_6
#define USE_LED_6 1
#endif
#define LED_6_GPIO PAL_PORT(LINE_NLED6)
#define LED_6_GPIO_PIN PAL_PAD(LINE_NLED6)
#define LED_6_GPIO_ON gpio_set
#define LED_6_GPIO_OFF gpio_clear
#endif
/*
@@ -308,6 +376,18 @@
#endif
#endif
/*
* ALARM defines
*/
#if defined(LINE_ALARM)
#define ALARM_GPIO PAL_PORT(LINE_ALARM)
#define ALARM_PIN PAL_PAD(LINE_ALARM)
#define ALARM_AF AF_LINE_SERVO1
#define ALARM_DRIVER CONCAT_BOARD_PARAM(PWMD, ALARM_TIM)
#define ALARM_CHANNEL (ALARM_TIM_CH-1)
#define ALARM_CONF CONCAT_BOARD_PARAM(pwmcfg, ALARM_TIM)
#endif
/*
* PWM input
*/
@@ -676,26 +756,26 @@
/**
* SDIO
*/
#if defined(LINE_SDIO_D0) && defined(LINE_SDIO_D1) && defined(LINE_SDIO_D2) && defined(LINE_SDIO_D3) && defined(LINE_SDIO_CK) && defined(LINE_SDIO_CMD)
#define SDIO_D0_PORT PAL_PORT(LINE_SDIO_D0)
#define SDIO_D0_PIN PAL_PAD(LINE_SDIO_D0)
#define SDIO_D1_PORT PAL_PORT(LINE_SDIO_D1)
#define SDIO_D1_PIN PAL_PAD(LINE_SDIO_D1)
#define SDIO_D2_PORT PAL_PORT(LINE_SDIO_D2)
#define SDIO_D2_PIN PAL_PAD(LINE_SDIO_D2)
#define SDIO_D3_PORT PAL_PORT(LINE_SDIO_D3)
#define SDIO_D3_PIN PAL_PAD(LINE_SDIO_D3)
#define SDIO_CK_PORT PAL_PORT(LINE_SDIO_CK)
#define SDIO_CK_PIN PAL_PAD(LINE_SDIO_CK)
#define SDIO_CMD_PORT PAL_PORT(LINE_SDIO_CMD)
#define SDIO_CMD_PIN PAL_PAD(LINE_SDIO_CMD)
// #if defined(LINE_SDIO_D0) && defined(LINE_SDIO_D1) && defined(LINE_SDIO_D2) && defined(LINE_SDIO_D3) && defined(LINE_SDIO_CK) && defined(LINE_SDIO_CMD)
// #define SDIO_D0_PORT PAL_PORT(LINE_SDIO_D0)
// #define SDIO_D0_PIN PAL_PAD(LINE_SDIO_D0)
// #define SDIO_D1_PORT PAL_PORT(LINE_SDIO_D1)
// #define SDIO_D1_PIN PAL_PAD(LINE_SDIO_D1)
// #define SDIO_D2_PORT PAL_PORT(LINE_SDIO_D2)
// #define SDIO_D2_PIN PAL_PAD(LINE_SDIO_D2)
// #define SDIO_D3_PORT PAL_PORT(LINE_SDIO_D3)
// #define SDIO_D3_PIN PAL_PAD(LINE_SDIO_D3)
// #define SDIO_CK_PORT PAL_PORT(LINE_SDIO_CK)
// #define SDIO_CK_PIN PAL_PAD(LINE_SDIO_CK)
// #define SDIO_CMD_PORT PAL_PORT(LINE_SDIO_CMD)
// #define SDIO_CMD_PIN PAL_PAD(LINE_SDIO_CMD)
#if defined(AF_LINE_SDIO_CMD)
#define SDIO_AF AF_LINE_SDIO_CMD
#else
#define SDIO_AF ((void)0)
#endif
#endif
// #if defined(AF_LINE_SDIO_CMD)
// #define SDIO_AF AF_LINE_SDIO_CMD
// #else
// #define SDIO_AF ((void)0)
// #endif
// #endif
#if defined(LINE_USB_VBUS)
#define SDLOG_USB_VBUS_PORT PAL_PORT(LINE_USB_VBUS)

View File

@@ -1,5 +1,5 @@
/*
ChibiOS - Copyright (C) 2006..2020 Giovanni Di Sirio
ChibiOS - Copyright (C) 2006..2023 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,7 @@
#define HALCONF_H
#define _CHIBIOS_HAL_CONF_
#define _CHIBIOS_HAL_CONF_VER_8_0_
#define _CHIBIOS_HAL_CONF_VER_8_4_
#include "mcuconf.h"
@@ -376,15 +376,18 @@
/*===========================================================================*/
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
* This option is recommended also if the SPI driver does not
* use a DMA channel and heavily loads the CPU.
* @brief Timeout before assuming a failure while waiting for card idle.
* @note Time is in milliseconds.
*/
#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__)
#define MMC_NICE_WAITING TRUE
#if !defined(MMC_IDLE_TIMEOUT_MS) || defined(__DOXYGEN__)
#define MMC_IDLE_TIMEOUT_MS 1000
#endif
/**
* @brief Mutual exclusion on the SPI bus.
*/
#if !defined(MMC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define MMC_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/

View File

@@ -45,9 +45,9 @@
static enum {STOP, CONNECT} cnxState = STOP;
bool sdio_connect(void)
bool sdio_connect(SDCDriver *sdc)
{
if (!sdc_lld_is_card_inserted(NULL)) {
if (!sdc_lld_is_card_inserted(sdc)) {
return FALSE;
}
@@ -57,12 +57,12 @@ bool sdio_connect(void)
// Try only 3 times to prevent hanging
for (uint8_t i = 0; i < 3; i++) {
sdcStart(&SDCD1, NULL);
if (sdcConnect(&SDCD1) == HAL_SUCCESS) {
sdcStart(sdc, NULL);
if (sdcConnect(sdc) == HAL_SUCCESS) {
cnxState = CONNECT;
return TRUE;
}
sdcStop(&SDCD1);
sdcStop(sdc);
chThdSleepMilliseconds(100);
}
@@ -70,21 +70,21 @@ bool sdio_connect(void)
}
bool sdio_disconnect(void)
bool sdio_disconnect(SDCDriver *sdc)
{
if (cnxState == STOP) {
return TRUE;
}
if (sdcDisconnect(&SDCD1)) {
if (sdcDisconnect(sdc)) {
return FALSE;
}
sdcStop(&SDCD1);
sdcStop(sdc);
cnxState = STOP;
return TRUE;
}
bool is_card_inserted(void)
bool is_card_inserted(SDCDriver *sdc)
{
return sdc_lld_is_card_inserted(NULL);
return sdc_lld_is_card_inserted(sdc);
}

View File

@@ -0,0 +1,33 @@
/*
* Copyright (C) 2023 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.
*/
#ifndef CHIBIOS_MCUCONF_H
#define CHIBIOS_MCUCONF_H
#include "board.h"
#if defined(MCUCONF_H7)
#include "mcuconf_h7.h"
#else
#include "mcuconf_board.h"
#endif
#endif /* CHIBIOS_MCUCONF_H */

View File

@@ -1,5 +1,5 @@
/*
ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
ChibiOS - Copyright (C) 2006..2023 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.
@@ -14,14 +14,21 @@
limitations under the License.
*/
#ifndef MCUCONF_H
#define MCUCONF_H
#ifndef MCUCONF_H7_H
#define MCUCONF_H7_H
/*
* Enforce old versions of the chip
*/
/* Always enforce the old version */
#define STM32_ENFORCE_H7_REV_XY
/* Default clock configuration */
#ifndef STM32_LSECLK
#define STM32_LSECLK 32768U
#endif
#ifndef STM32_LSEDRV
#define STM32_LSEDRV (3U << 3U)
#endif
/*
* STM32H7xx drivers configuration.
* The following settings override the default settings present in
@@ -44,6 +51,7 @@
#define STM32H755_MCUCONF
#define STM32H747_MCUCONF
#define STM32H757_MCUCONF
#define STM32H750_MCUCONF
/*
* General settings.
@@ -54,7 +62,7 @@
/*
* Memory attributes settings.
*/
#define STM32_NOCACHE_ENABLE TRUE
#define STM32_NOCACHE_ENABLE FALSE
#define STM32_NOCACHE_MPU_REGION MPU_REGION_6
#define STM32_NOCACHE_RBAR 0x24000000U
#define STM32_NOCACHE_RASR MPU_RASR_SIZE_64K
@@ -68,7 +76,11 @@
#define STM32_VOS STM32_VOS_SCALE1
#define STM32_PWR_CR1 (PWR_CR1_SVOS_1 | PWR_CR1_SVOS_0)
#define STM32_PWR_CR2 (PWR_CR2_BREN)
#if SMPS_PWR
#define STM32_PWR_CR3 (PWR_CR3_SMPSEN | PWR_CR3_USB33DEN)
#else
#define STM32_PWR_CR3 (PWR_CR3_LDOEN | PWR_CR3_USB33DEN)
#endif
#define STM32_PWR_CPUCR 0
/*
@@ -87,6 +99,41 @@
* PLLs static settings.
* Reading STM32 Reference Manual is required.
*/
#if STM32_HSECLK == 16000000U
#define STM32_PLLSRC STM32_PLLSRC_HSE_CK
#define STM32_PLLCFGR_MASK ~0
#define STM32_PLL1_ENABLED TRUE
#define STM32_PLL1_P_ENABLED TRUE
#define STM32_PLL1_Q_ENABLED TRUE
#define STM32_PLL1_R_ENABLED TRUE
#define STM32_PLL1_DIVM_VALUE 2
#define STM32_PLL1_DIVN_VALUE 100
#define STM32_PLL1_FRACN_VALUE 0
#define STM32_PLL1_DIVP_VALUE 2
#define STM32_PLL1_DIVQ_VALUE 10
#define STM32_PLL1_DIVR_VALUE 2
#define STM32_PLL2_ENABLED TRUE
#define STM32_PLL2_P_ENABLED TRUE
#define STM32_PLL2_Q_ENABLED TRUE
#define STM32_PLL2_R_ENABLED TRUE
#define STM32_PLL2_DIVM_VALUE 2
#define STM32_PLL2_DIVN_VALUE 75
#define STM32_PLL2_FRACN_VALUE 0
#define STM32_PLL2_DIVP_VALUE 3
#define STM32_PLL2_DIVQ_VALUE 6
#define STM32_PLL2_DIVR_VALUE 3
#define STM32_PLL3_ENABLED TRUE
#define STM32_PLL3_P_ENABLED FALSE
#define STM32_PLL3_Q_ENABLED TRUE
#define STM32_PLL3_R_ENABLED TRUE
#define STM32_PLL3_DIVM_VALUE 4
#define STM32_PLL3_DIVN_VALUE 72
#define STM32_PLL3_FRACN_VALUE 0
#define STM32_PLL3_DIVP_VALUE 2
#define STM32_PLL3_DIVQ_VALUE 6
#define STM32_PLL3_DIVR_VALUE 9
#elif STM32_HSECLK == 24000000U
#define STM32_PLLSRC STM32_PLLSRC_HSE_CK
#define STM32_PLLCFGR_MASK ~0
#define STM32_PLL1_ENABLED TRUE
@@ -119,6 +166,7 @@
#define STM32_PLL3_DIVP_VALUE 2
#define STM32_PLL3_DIVQ_VALUE 6
#define STM32_PLL3_DIVR_VALUE 9
#endif /* STM32_HSECLK */
/*
* Core clocks dynamic settings (can be changed at runtime).
@@ -255,7 +303,6 @@
#else
#define STM32_CAN_USE_FDCAN2 FALSE
#endif
#define STM32_CAN_USE_FDCAN3 FALSE
/*
* DAC driver system settings.
@@ -311,7 +358,7 @@
#else
#define STM32_I2C_USE_I2C4 FALSE
#endif
#define STM32_I2C_ISR_LIMIT 6
//TODO #define STM32_I2C_ISR_LIMIT 6
#define STM32_I2C_BUSY_TIMEOUT 0
#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
@@ -319,8 +366,6 @@
#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C4_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C4_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_I2C_I2C4_RX_BDMA_STREAM 1
#define STM32_I2C_I2C4_TX_BDMA_STREAM 2
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
@@ -363,17 +408,41 @@
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
#if USE_PWM_TIM1 || USE_DSHOT_TIM1
#define STM32_PWM_USE_TIM1 TRUE
#else
#define STM32_PWM_USE_TIM1 FALSE
#endif
#if USE_PWM_TIM2 || USE_DSHOT_TIM2
#define STM32_PWM_USE_TIM2 TRUE
#else
#define STM32_PWM_USE_TIM2 FALSE
#endif
#if USE_PWM_TIM3 || USE_DSHOT_TIM3
#define STM32_PWM_USE_TIM3 TRUE
#else
#define STM32_PWM_USE_TIM3 FALSE
#endif
#if USE_PWM_TIM4 || USE_DSHOT_TIM4
#define STM32_PWM_USE_TIM4 TRUE
#else
#define STM32_PWM_USE_TIM4 FALSE
#endif
#if USE_PWM_TIM5 || USE_DSHOT_TIM5
#define STM32_PWM_USE_TIM5 TRUE
#else
#define STM32_PWM_USE_TIM5 FALSE
#endif
#if USE_PWM_TIM8 || USE_DSHOT_TIM8
#define STM32_PWM_USE_TIM8 TRUE
#else
#define STM32_PWM_USE_TIM8 FALSE
#define STM32_PWM_USE_TIM9 FALSE
#define STM32_PWM_USE_TIM10 FALSE
#define STM32_PWM_USE_TIM11 FALSE
#endif
#if USE_PWM_TIM12 || USE_DSHOT_TIM12
#define STM32_PWM_USE_TIM12 TRUE
#else
#define STM32_PWM_USE_TIM12 FALSE
#endif
#define STM32_PWM_USE_TIM13 FALSE
#define STM32_PWM_USE_TIM14 FALSE
#define STM32_PWM_USE_TIM15 FALSE
@@ -391,15 +460,22 @@
/*
* SDC driver system settings.
*/
#define STM32_SDMMC_MAXCLK 200000000
#if USE_SDCD1
#define STM32_SDC_USE_SDMMC1 TRUE
#else
#define STM32_SDC_USE_SDMMC1 FALSE
#endif
#if USE_SDCD2
#define STM32_SDC_USE_SDMMC2 TRUE
#else
#define STM32_SDC_USE_SDMMC2 FALSE
#endif
#define STM32_SDC_SDMMC_UNALIGNED_SUPPORT TRUE
#define STM32_SDC_SDMMC_WRITE_TIMEOUT 6000000
#define STM32_SDC_SDMMC_READ_TIMEOUT 6000000
#define STM32_SDC_SDMMC_CLOCK_DELAY 20
#define STM32_SDC_SDMMC_PWRSAV TRUE
#define STM32_SDC_FORCE_25MHZ TRUE
//TODO #define STM32_SDC_FORCE_25MHZ TRUE
/*
* SERIAL driver system settings.
@@ -435,16 +511,29 @@
#define STM32_SERIAL_USE_USART6 FALSE
#endif
#if USE_UART7
#define STM32_SERIAL_USE_UART7 TRUE
#define STM32_SERIAL_USE_UART7 TRUE
#else
#define STM32_SERIAL_USE_UART7 FALSE
#define STM32_SERIAL_USE_UART7 FALSE
#endif
#if USE_UART8
#define STM32_SERIAL_USE_UART8 TRUE
#define STM32_SERIAL_USE_UART8 TRUE
#else
#define STM32_SERIAL_USE_UART8 FALSE
#define STM32_SERIAL_USE_UART8 FALSE
#endif
#define STM32_SERIAL_USE_LPUART1 FALSE
#define STM32_SERIAL_USE_LPUART1 FALSE
/*
* SIO driver system settings.
*/
#define STM32_SIO_USE_USART1 FALSE
#define STM32_SIO_USE_USART2 FALSE
#define STM32_SIO_USE_USART3 FALSE
#define STM32_SIO_USE_UART4 FALSE
#define STM32_SIO_USE_UART5 FALSE
#define STM32_SIO_USE_USART6 FALSE
#define STM32_SIO_USE_UART7 FALSE
#define STM32_SIO_USE_UART8 FALSE
#define STM32_SIO_USE_LPUART1 FALSE
/*
* SPI driver system settings.
@@ -469,8 +558,16 @@
#else
#define STM32_SPI_USE_SPI4 FALSE
#endif
#if USE_SPI4
#define STM32_SPI_USE_SPI5 TRUE
#else
#define STM32_SPI_USE_SPI5 FALSE
#endif
#if USE_SPI6
#define STM32_SPI_USE_SPI6 TRUE
#else
#define STM32_SPI_USE_SPI6 FALSE
#endif
#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
@@ -481,8 +578,8 @@
#define STM32_SPI_SPI4_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI5_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI5_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI6_RX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI6_TX_DMA_STREAM STM32_DMA_STREAM_ID_ANY
#define STM32_SPI_SPI6_RX_BDMA_STREAM STM32_BDMA_STREAM_ID_ANY
#define STM32_SPI_SPI6_TX_BDMA_STREAM STM32_BDMA_STREAM_ID_ANY
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
@@ -501,9 +598,7 @@
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#ifndef STM32_ST_USE_TIMER
#define STM32_ST_USE_TIMER 5
#endif
/*
* TRNG driver system settings.
@@ -568,6 +663,7 @@
*/
#define STM32_WSPI_USE_QUADSPI1 FALSE
#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE ((STM32_QSPICLK / HAL_QSPI1_CLK) - 1)
#define STM32_WSPI_SET_CR_SSHIFT TRUE
#define STM32_WSPI_QUADSPI1_MDMA_CHANNEL STM32_MDMA_CHANNEL_ID_ANY
#define STM32_WSPI_QUADSPI1_MDMA_PRIORITY 1
#define STM32_WSPI_MDMA_ERROR_HOOK(wspip) osalSysHalt("MDMA failure")
@@ -580,4 +676,4 @@
#define SDLOG_NUM_FILES 2
#define SDLOG_ALL_BUFFERS_SIZE (SDLOG_NUM_FILES*16*1024)
#endif /* MCUCONF_H */
#endif /* MCUCONF_H7_H */

View File

@@ -25,6 +25,7 @@ HEADER
* MCU type as defined in the ST header.
*/
#define STM32H743xx
#define MCUCONF_H7
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
#ifndef ADC_CHANNEL_VSUPPLY

View File

@@ -39,6 +39,7 @@
* MCU type as defined in the ST header.
*/
#define STM32H743xx
#define MCUCONF_H7
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
#ifndef ADC_CHANNEL_VSUPPLY
@@ -57,7 +58,7 @@
/* Default powerbrick values */
#define DefaultVoltageOfAdc(adc) ((3.3f/65536.0f) * 13.38f * adc)
#define DefaultVBoardOfAdc(adc) ((3.3f/65536.0f) * 1.89036 * adc)
#define DefaultVBoardOfAdc(adc) ((3.3f/65536.0f) * 1.89036f * adc)
#define DefaultMilliAmpereOfAdc(adc) ((3.3f/65536.0f) * 39.877f * adc)
/* Battery monitoring for file closing */

View File

@@ -401,7 +401,6 @@
/*
* SDC driver system settings.
*/
#define STM32_SDMMC_MAXCLK 200000000
#define STM32_SDC_USE_SDMMC1 TRUE
#define STM32_SDC_USE_SDMMC2 FALSE
#define STM32_SDC_SDMMC_UNALIGNED_SUPPORT TRUE

View File

@@ -502,4 +502,4 @@
#define SDLOG_NUM_FILES 2
#define SDLOG_ALL_BUFFERS_SIZE (SDLOG_NUM_FILES*16*1024)
#endif /* MCUCONF_H */
#endif /* MCUCONF_H */

View File

@@ -0,0 +1,9 @@
# file board.h is generated from file board.cfg by a script which is hosted here :
# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/boardGen.pl
# documentation is here :
# https://github.com/alex31/chibios_enac_various_common/blob/master/TOOLS/DOC/boardGen.pdf
board.h: board.cfg Makefile
boardGen.pl --no-pp-line $< $@

View File

@@ -0,0 +1,219 @@
MCU_MODEL = STM32H753IIKx
CHIBIOS_VERSION = 3.0
HEADER
/*
* Board identifier.
*/
#define BOARD_PX4FMU_6X
#define BOARD_NAME "PX4FMU 6X"
/*
* Board oscillators-related settings.
*/
#if !defined(STM32_LSECLK)
#define STM32_LSECLK 32768U
#endif
#define STM32_LSEDRV (3U << 3U)
#if !defined(STM32_HSECLK)
#define STM32_HSECLK 16000000U
#endif
/*
* MCU type as defined in the ST header.
*/
#define STM32H753xx
#define MCUCONF_H7
/*
* PWM TIM defines
* enable TIM4, TIM5 and TIM12 by default
*/
#ifndef USE_PWM_TIM4
#define USE_PWM_TIM4 1
#endif
#ifndef USE_PWM_TIM5
#define USE_PWM_TIM5 1
#endif
#ifndef USE_PWM_TIM12
//#define USE_PWM_TIM12 1
#endif
CONFIG
# PIN NAME PERIPH_TYPE AF_NUMBER or
# PIN NAME FUNCTION PP_or_OPENDRAIN PIN_SPEED PULL_RESISTOR INITIAL_LEVEL AF_NUMBER
# SPEED : SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH
#
# DEFAULT AND SYS
#
# 'SYS' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'ADC' => ['ANALOG', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_LOW'],
# 'PWM' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_LOW'],
# 'ICU' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'I2C' => ['ALTERNATE', 'OPENDRAIN', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'],
# 'SPI' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'UART' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'],
# 'OTG' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'ETH' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'FSMC' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'SDIO' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'PULLUP', 'LEVEL_HIGH'],
# 'SDIOCK' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'CAN' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'DCMI' => ['ALTERNATE', 'PUSHPULL', 'SPEED_HIGH', 'FLOATING', 'LEVEL_HIGH'],
# 'LED' => ['OUTPUT', 'PUSHPULL', 'SPEED_VERYLOW', 'FLOATING', 'LEVEL_LOW'],
# 'PASSIVE' => ['INPUT', 'PUSHPULL', 'SPEED_VERYLOW', 'FLOATING', 'LEVEL_LOW']);
#
# SYSTEM
A13 SWDIO SYS AF:DEBUG_JTMS-SWDIO
A14 SWCLK SYS AF:DEBUG_JTCK-SWCLK
H00 OSC_IN SYS AF0
H01 OSC_OUT SYS AF0
# DEFAULT
DEFAULT INPUT PUSHPULL SPEED_VERYLOW PULLDOWN LEVEL_LOW AF0
# ACTIVE PINS
PA00 ADC1 ADC ADC1_INP16 () # SCALED1_V3V3
PA01 ETH_RMII_REF_CLK PASSIVE # Not used
PA02 ETH_MDIO PASSIVE # Not used
PA03 UART2 UART AF:USART2_RX () # TELEM3
PA04 ADC2 ADC ADC1_INP18 () # SCALED2_V3V3
PA05 SPI1_SCK SPI AF:SPI1_SCK # IMU1
PA06 SPI6_MISO SPI AF:SPI6_MISO # EXTERNAL1
PA07 ETH_RMII_CRS_DV PASSIVE # Not used
PA08 I2C3_SCL I2C AF:I2C3_SCL # MS5611, external
PA09 USB_VBUS INPUT PULLDOWN # USB
PA10 SPI2_DRDY PASSIVE # ICM42688 Not used
PA11 USB_DM OTG AF:USB_OTG_FS_DM # USB
PA12 USB_DP OTG AF:USB_OTG_FS_DP # USB
PB00 ADC3 ADC ADC1_INP9 () # SCALED3_V3V3
PB01 ADC5 ADC ADC1_INP5 () # VDD_5V_SENS
PB02 SPI3_MOSI SPI AF:SPI3_MOSI # BMI088
PB03 SPI6_SCK SPI AF:SPI6_SCK # EXTERNAL1
PB04 SDIO_D3 SDIO AF:SDMMC2_D3 # MICROSD
PB05 SPI1_MOSI SPI AF:SPI1_MOSI # IMU1
PB06 UART1_TX UART AF:USART1_TX # GPS1
PB07 UART1_RX UART AF:USART1_RX # GPS1
PB08 I2C1_SCL I2C AF:I2C1_SCL # GPS+MAG
PB09 I2C1_SDA I2C AF:I2C1_SDA # GPS+MAG
PB10 IMU_HEATER OUTPUT PUSHPULL SPEED_HIGH FLOATING LEVEL_LOW # HEATER
PB11 ETH_RMII_TX_EN PASSIVE # Not used
PB12 CAN2_RX CAN AF:FDCAN2_RX # CAN2
PB13 CAN2_TX CAN AF:FDCAN2_TX # CAN2
PB14 SDIO_D0 SDIO AF:SDMMC2_D0 # MICROSD
PB15 SDIO_D1 SDIO AF:SDMMC2_D1 # MICROSD
PC00 NFC_GPIO PASSIVE # NFC_GPIO
PC01 ETH_MDC PASSIVE # Not used
PC02 ADC6 ADC ADC3_INP0 () # ADC1_6V6 Analog 12
PC03 ADC7 ADC ADC3_INP1 () # ADC1_3V3 Analog 13
PC04 ETH_RMII_RXD0 PASSIVE # Not used
PC05 ETH_RMII_RXD1 PASSIVE # Not used
PC06 UART6_TX UART AF:USART6_TX # IOMCU
PC07 UART6_RX UART AF:USART6_RX # IOMCU
PC08 UART5_RTS PASSIVE # TELEM2
PC09 UART5_CTS PASSIVE # TELEM2
PC10 SPI3_SCK SPI AF:SPI3_SCK # BMI088
PC11 SPI3_MISO SPI AF:SPI3_MISO # BMI088
PC12 UART5_TX UART AF:UART5_TX # TELEM2
PC13 VDD_3V3_SD_CARD_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # VDD_3V3_SD_CARD_EN
PD00 CAN1_RX CAN AF:FDCAN1_RX # CAN1
PD01 CAN1_TX CAN AF:FDCAN1_TX # CAN1
PD02 UART5_RX UART AF:UART5_RX # TELEM2
PD03 UART2_CTS PASSIVE # TELEM3
PD04 UART2_RTS PASSIVE # TELEM3
PD05 UART2_TX UART AF:USART2_TX # TELEM3
PD06 SDIO_CK SDIO AF:SDMMC2_CK # MICROSD
PD07 SDIO_CMD SDIO AF:SDMMC2_CMD # MICROSD
PD08 UART3_TX UART AF:USART3_TX # DEBUG
PD09 UART3_RX UART AF:USART3_RX # DEBUG
PD10 LED4 LED # LED_SAFETY
PD13 SERVO5 PWM AF:TIM4_CH2 ()
PD14 SERVO6 PWM AF:TIM4_CH3 ()
PE00 UART8_RX UART AF:UART8_RX # GPS2
PE01 UART8_TX UART AF:UART8_TX # GPS2
PE03 LED1 LED # LED_RED
PE04 LED2 LED # LED_GREEN
PE05 LED3 LED # LED_BLUE
PE06 NARMED PASSIVE # ARMED INVERTED OUTPUT
PE07 VDD_3V3_SENSORS3_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # VDD_3V3_SENSORS3_EN
PE08 UART7_TX UART AF:UART7_TX # TELEM1
PE10 UART7_CTS PASSIVE # TELEM1
PE11 FMU_CAP1 PASSIVE # FMU_CAP1
PE12 SPI4_SCK SPI AF:SPI4_SCK # UNUSED
PE13 SPI4_MISO SPI AF:SPI4_MISO # UNUSED
PE14 SPI4_MOSI SPI AF:SPI4_MOSI # UNUSED
PE15 VDD_5V_PERIPH_OC PASSIVE # INV
PF00 I2C2_SDA I2C AF:I2C2_SDA # GPS2+MAG
PF01 I2C2_SCL I2C AF:I2C2_SCL # GPS2+MAG
PF03 SPI4_DRDY1 PASSIVE # UNUSED
PF04 VDD_3V3_SENSORS2_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # VDD_3V3_SENSORS2_EN
PF05 SAFETY_IN INPUT PULLDOWN # SAFETY
PF06 UART7_RX UART AF:UART7_RX # TELEM1
PF07 SPI5_SCK SPI AF:SPI5_SCK # FRAM
PF08 UART7_RTS PASSIVE # TELEM1
PF09 ALARM PWM AF:TIM17_CH1N () # ALARM
PF11 SPI5_MOSI SPI AF:SPI5_MOSI # FRAM
PF12 ADC4 ADC ADC1_INP6 () # SCALED4_V3V3
PF13 VDD_5V_HIPOWER_OC PASSIVE # INV
PF14 I2C4_SCL I2C AF:I2C4_SCL # INTERNAL
PF15 I2C4_SDA I2C AF:I2C4_SDA # INTERNAL
PG00 HW_VER_REV_DRIVE PASSIVE # HW_VER_REV_DRIVE
PG01 VDD_BRICK_VALID PASSIVE # VDD_BRICK_VALID INV
PG02 VDD_BRICK2_VALID PASSIVE # VDD_BRICK2_VALID INV
PG03 VDD_BRICK3_VALID PASSIVE # VDD_BRICK3_VALID INV
PG04 VDD_5V_PERIPH_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW # VDD_5V_PERIPH_EN INV
PG05 DRDY1_BMP388 PASSIVE # DRDY1_BMP388
PG07 SPI_SLAVE6 PASSIVE # SPI_SLAVE6_SELECT
PG08 VDD_3V3_SENSORS4_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # VDD_3V3_SENSORS4_EN
PG09 SPI1_MISO SPI AF:SPI1_MISO # IMU1
PG10 VDD_5V_HIPOWER_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_LOW # VDD_5V_HIPOWER_EN INV
PG11 SDIO_D2 SDIO AF:SDMMC2_D2 # MICROSD
PG12 ETH_RMII_TXD1 PASSIVE # Not used
PG13 ETH_RMII_TXD0 PASSIVE # Not used
PG14 SPI6_MOSI SPI AF:SPI6_MOSI # EXTERNAL1
PG15 ETH_POWER_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # ETH_POWER_EN INV
PH02 SPEKTRUM_PWR_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # SPEKTRUM_PWR_EN
PH03 HW_VER_SENS PASSIVE # HW_VER_SENS
PH04 HW_REV_SENS PASSIVE # HW_REV_SENS
PH05 SPI_SLAVE2 PASSIVE # SPI_SLAVE2_SELECT
#PH06 SERVO7 PWM AF:TIM12_CH1 ()
PH07 SPI5_MISO SPI AF:SPI5_MISO # FRAM
PH08 I2C3_SDA I2C AF:I2C3_SDA # MS5611, external
#PH09 SERVO8 PWM AF:TIM12_CH2 ()
PH10 SERVO4 PWM AF:TIM5_CH1 ()
PH11 SERVO3 PWM AF:TIM5_CH2 ()
PH12 SERVO2 PWM AF:TIM5_CH3 ()
PH13 UART4_TX UART AF:UART4_TX # UART4
PH14 UART4_RX UART AF:UART4_RX # UART4
PH15 SPI_SLAVE5 PASSIVE # SPI_SLAVE5_SELECT
PI00 SERVO1 PWM AF:TIM5_CH4 ()
PI01 SPI2_SCK SPI AF:SPI2_SCK # ICM42688
PI02 SPI2_MISO SPI AF:SPI2_MISO # ICM42688
PI03 SPI2_MOSI SPI AF:SPI2_MOSI # ICM42688
PI04 SPI_SLAVE3 PASSIVE # SPI_SLAVE3_SELECT
PI05 PWM_INPUT1 ICU AF:TIM8_CH1 () # PWM_INPUT1
PI06 SPI3_DRDY1 PASSIVE # BMI088
PI07 SPI3_DRDY2 PASSIVE # BMI088
PI08 SPI_SLAVE4 PASSIVE # SPI_SLAVE4_SELECT
PI09 SPI_SLAVE1 PASSIVE # SPI_SLAVE1_SELECT
PI10 SPI_SLAVE7 PASSIVE # SPI_SLAVE7_SELECT
PI11 VDD_3V3_SENSORS1_EN OUTPUT PUSHPULL SPEED_VERYLOW FLOATING LEVEL_HIGH # VDD_3V3_SENSORS1_EN
# GROUPS
GROUP ENERGY_SAVE_INPUTS %NAME=~/^SERVO[0-9]+|LED[0-9]+|SPI_SLAVE[0-9]+$/
GROUP ENERGY_SAVE_LOWS %NAME=~/^VDD_3V3_SENSORS[0-9]+_EN|ALARM|ETH_POWER_EN$/

File diff suppressed because it is too large Load Diff

View File

@@ -27,17 +27,19 @@
#ifndef MCU_PERIPH_SDIO_H
#define MCU_PERIPH_SDIO_H
typedef struct SDCDriver SDCDriver;
/** Connect a SD card on SDIO peripheral
*/
bool sdio_connect(void);
bool sdio_connect(SDCDriver *sdc);
/** Disconnect a SD card on SDIO peripheral
*/
bool sdio_disconnect(void);
bool sdio_disconnect(SDCDriver *sdc);
/** Check if a SD card is inserted
*/
bool is_card_inserted (void);
bool is_card_inserted(SDCDriver *sdc);
#endif

View File

@@ -399,6 +399,18 @@
#define IMU_ICM42688_ID 24
#endif
#ifndef IMU_PIXHAWK1_ID
#define IMU_PIXHAWK1_ID 25
#endif
#ifndef IMU_PIXHAWK2_ID
#define IMU_PIXHAWK2_ID 26
#endif
#ifndef IMU_PIXHAWK3_ID
#define IMU_PIXHAWK3_ID 27
#endif
// prefiltering with OneEuro filter
#ifndef IMU_F1E_ID
#define IMU_F1E_ID 30

View File

@@ -0,0 +1,124 @@
/*
* Copyright (C) 2022 Freek van tieen <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.
*/
/**
* @file modules/imu/imu_cube.c
* Driver for the IMU's in the Cube autopilots.
*/
#include "generated/modules.h"
#include "modules/imu/imu.h"
#include "modules/core/abi.h"
#include "mcu_periph/spi.h"
#include "peripherals/invensense2.h"
#include "peripherals/invensense3.h"
static struct invensense3_t imu1;
static struct invensense3_t imu2;
static struct invensense2_t imu3;
void imu_pixhawk6x_init(void)
{
struct Int32RMat rmat;
struct Int32Eulers eulers;
/* IMU 1 */
imu1.abi_id = IMU_PIXHAWK1_ID;
imu1.parser = INVENSENSE3_PARSER_FIFO;
imu1.bus = INVENSENSE3_SPI;
imu1.spi.p = &PIXHAWK6X_IMU1_SPI_DEV;
imu1.spi.slave_idx = PIXHAWK6X_IMU1_SPI_SLAVE_IDX;
imu1.gyro_odr = INVENSENSE3_GYRO_ODR_4KHZ;
imu1.gyro_range = INVENSENSE3_GYRO_RANGE_2000DPS;
imu1.accel_odr = INVENSENSE3_ACCEL_ODR_4KHZ;
imu1.accel_range = INVENSENSE3_ACCEL_RANGE_32G;
imu1.gyro_aaf = 977; // ~ODR/4
imu1.accel_aaf = 213; // Fixed
invensense3_init(&imu1);
// Rotation
eulers.phi = ANGLE_BFP_OF_REAL(0);
eulers.theta = ANGLE_BFP_OF_REAL(0);
eulers.psi = ANGLE_BFP_OF_REAL(RadOfDeg(90));
int32_rmat_of_eulers(&rmat, &eulers);
imu_set_defaults_gyro(IMU_PIXHAWK1_ID, &rmat, NULL, NULL);
imu_set_defaults_accel(IMU_PIXHAWK1_ID, &rmat, NULL, NULL);
/* IMU 2 */
imu2.abi_id = IMU_PIXHAWK2_ID;
imu2.parser = INVENSENSE3_PARSER_FIFO;
imu2.bus = INVENSENSE3_SPI;
imu2.spi.p = &PIXHAWK6X_IMU2_SPI_DEV;
imu2.spi.slave_idx = PIXHAWK6X_IMU2_SPI_SLAVE_IDX;
imu2.gyro_odr = INVENSENSE3_GYRO_ODR_4KHZ;
imu2.gyro_range = INVENSENSE3_GYRO_RANGE_2000DPS;
imu2.accel_odr = INVENSENSE3_ACCEL_ODR_4KHZ;
imu2.accel_range = INVENSENSE3_ACCEL_RANGE_32G;
imu2.gyro_aaf = 977; // ~ODR/4
imu2.accel_aaf = 213; // Fixed
invensense3_init(&imu2);
// Rotation
eulers.phi = ANGLE_BFP_OF_REAL(0);
eulers.theta = ANGLE_BFP_OF_REAL(RadOfDeg(180));
eulers.psi = ANGLE_BFP_OF_REAL(RadOfDeg(90));
int32_rmat_of_eulers(&rmat, &eulers);
imu_set_defaults_gyro(IMU_PIXHAWK2_ID, &rmat, NULL, NULL);
imu_set_defaults_accel(IMU_PIXHAWK2_ID, &rmat, NULL, NULL);
/* IMU 3 */
imu3.abi_id = IMU_PIXHAWK3_ID;
imu3.bus = INVENSENSE2_SPI;
imu3.spi.p = &PIXHAWK6X_IMU3_SPI_DEV;
imu3.spi.slave_idx = PIXHAWK6X_IMU3_SPI_SLAVE_IDX;
imu3.gyro_dlpf = INVENSENSE2_GYRO_DLPF_229HZ;
imu3.gyro_range = INVENSENSE2_GYRO_RANGE_4000DPS;
imu3.accel_dlpf = INVENSENSE2_ACCEL_DLPF_265HZ;
imu3.accel_range = INVENSENSE2_ACCEL_RANGE_30G;
invensense2_init(&imu3);
// Rotation
eulers.phi = ANGLE_BFP_OF_REAL(0),
eulers.theta = ANGLE_BFP_OF_REAL(0);
eulers.psi = ANGLE_BFP_OF_REAL(RadOfDeg(180));
int32_rmat_of_eulers(&rmat, &eulers);
imu_set_defaults_gyro(IMU_PIXHAWK3_ID, &rmat, NULL, NULL);
imu_set_defaults_accel(IMU_PIXHAWK3_ID, &rmat, NULL, NULL);
}
void imu_pixhawk6x_periodic(void)
{
invensense3_periodic(&imu1);
invensense3_periodic(&imu2);
invensense2_periodic(&imu3);
}
void imu_pixhawk6x_event(void)
{
invensense3_event(&imu1);
invensense3_event(&imu2);
invensense2_event(&imu3);
}

View File

@@ -0,0 +1,36 @@
/*
* 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.
*/
/**
* @file modules/imu/imu_pixhawk6x.h
* Driver for the IMU's in the Pixhawk 6X autopilots.
*/
#ifndef IMU_PIXHAWK6X_H
#define IMU_PIXHAWK6X_H
#include "std.h"
extern void imu_pixhawk6x_init(void);
extern void imu_pixhawk6x_periodic(void);
extern void imu_pixhawk6x_event(void);
#endif /* IMU_PIXHAWK6X_H */

View File

@@ -61,8 +61,6 @@
#error sdlog_chibios need USE_ADC_WATCHDOG in order to properly close files when power is unplugged
#endif
#define DefaultAdcOfVoltage(voltage) ((uint32_t) (voltage/(DefaultVoltageOfAdc(1))))
static const uint16_t V_ALERT = DefaultAdcOfVoltage(5.5f);
static const char PPRZ_LOG_NAME[] = "pprzlog_";
static const char PPRZ_LOG_DIR[] = "PPRZ";
@@ -72,15 +70,6 @@ static const char PPRZ_LOG_DIR[] = "PPRZ";
static IN_DMA_SECTION(THD_WORKING_AREA(wa_thd_startlog, 4096));
static __attribute__((noreturn)) void thd_startlog(void *arg);
/*
* Bat survey thread
*/
static THD_WORKING_AREA(wa_thd_bat_survey, 1024);
static __attribute__((noreturn)) void thd_bat_survey(void *arg);
static void powerOutageIsr(void);
event_source_t powerOutageSource;
event_listener_t powerOutageListener;
bool sdOk = false;
FileDes pprzLogFile = -1;
@@ -240,6 +229,56 @@ void sdlog_chibios_finish(const bool flush)
chibios_sdlog_status = SDLOG_STOPPED;
}
#if defined(SDLOG_BAT_ADC) && defined(SDLOG_BAT_CHAN)
/*
* Bat survey thread
*/
static THD_WORKING_AREA(wa_thd_bat_survey, 1024);
static __attribute__((noreturn)) void thd_bat_survey(void *arg);
static void powerOutageIsr(void);
event_source_t powerOutageSource;
event_listener_t powerOutageListener;
#define DefaultAdcOfVoltage(voltage) ((uint32_t) (voltage/(DefaultVoltageOfAdc(1))))
static const uint16_t V_ALERT = DefaultAdcOfVoltage(5.5f);
/*
powerOutageIsr is called within a lock zone from an isr, so no lock/unlock is needed
*/
static void powerOutageIsr(void)
{
chEvtBroadcastI(&powerOutageSource);
}
static void thd_bat_survey(void *arg)
{
(void)arg;
chRegSetThreadName("battery survey");
chEvtRegister(&powerOutageSource, &powerOutageListener, 1);
chThdSleepMilliseconds(2000);
register_adc_watchdog(&SDLOG_BAT_ADC, SDLOG_BAT_CHAN, V_ALERT, &powerOutageIsr);
chEvtWaitOne(EVENT_MASK(1));
// Only try to energy save is it is really a problem and not powered through USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
// disable all required periph to save energy and maximize chance to flush files
// to mass storage and avoid infamous dirty bit on filesystem
mcu_energy_save();
}
// in case of powerloss, we should go fast and avoid to flush ram buffer
sdlog_chibios_finish(false);
// Only put to deep sleep in case there is no power on the USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
mcu_reboot(MCU_REBOOT_POWEROFF);
}
chThdExit(0);
while (true); // never goes here, only to avoid compiler warning: 'noreturn' function does return
}
#endif
static void thd_startlog(void *arg)
{
(void) arg;
@@ -281,10 +320,12 @@ static void thd_startlog(void *arg)
}
if (sdOk) {
#if defined(SDLOG_BAT_ADC) && defined(SDLOG_BAT_CHAN)
// Create Battery Survey Thread with event
chEvtObjectInit(&powerOutageSource);
chThdCreateStatic(wa_thd_bat_survey, sizeof(wa_thd_bat_survey),
NORMALPRIO + 2, thd_bat_survey, NULL);
#endif
chibios_sdlog_status = SDLOG_RUNNING;
} else {
@@ -329,43 +370,6 @@ static void thd_startlog(void *arg)
}
static void thd_bat_survey(void *arg)
{
(void)arg;
chRegSetThreadName("battery survey");
chEvtRegister(&powerOutageSource, &powerOutageListener, 1);
chThdSleepMilliseconds(2000);
register_adc_watchdog(&SDLOG_BAT_ADC, SDLOG_BAT_CHAN, V_ALERT, &powerOutageIsr);
chEvtWaitOne(EVENT_MASK(1));
// Only try to energy save is it is really a problem and not powered through USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
// disable all required periph to save energy and maximize chance to flush files
// to mass storage and avoid infamous dirty bit on filesystem
mcu_energy_save();
}
// in case of powerloss, we should go fast and avoid to flush ram buffer
sdlog_chibios_finish(false);
// Only put to deep sleep in case there is no power on the USB
if (palReadPad(SDLOG_USB_VBUS_PORT, SDLOG_USB_VBUS_PIN) == PAL_LOW) {
mcu_reboot(MCU_REBOOT_POWEROFF);
}
chThdExit(0);
while (true); // never goes here, only to avoid compiler warning: 'noreturn' function does return
}
/*
powerOutageIsr is called within a lock zone from an isr, so no lock/unlock is needed
*/
static void powerOutageIsr(void)
{
chEvtBroadcastI(&powerOutageSource);
}
void logger_log_msg_up(uint8_t* buf) {
uint8_t ac_id = pprzlink_get_DL_INFO_MSG_UP_ac_id(buf);
if(ac_id != AC_ID && ac_id != 0xFF) {

View File

@@ -243,11 +243,11 @@ SdioError sdLogInit(uint32_t *freeSpaceInKo)
}
sdio_connect();
sdio_connect(&SDLOG_SDIO);
chThdSleepMilliseconds(10);
sdio_disconnect();
sdio_disconnect(&SDLOG_SDIO);
if (sdio_connect() == FALSE) {
if (sdio_connect(&SDLOG_SDIO) == FALSE) {
return storageStatus = SDLOG_NOCARD;
}
@@ -294,7 +294,7 @@ SdioError sdLogFinish(void)
}
// if we mount, unmount, don't disconnect sdio
/* if (sdio_disconnect () == FALSE) */
/* if (sdio_disconnect (&SDLOG_SDIO) == FALSE) */
/* return SDLOG_NOCARD; */
return storageStatus = SDLOG_OK;

View File

@@ -63,7 +63,7 @@ static void usbActivity(bool active __attribute__((unused)))
/* USB mass storage configuration */
static USBMassStorageConfig msdConfig = {
&USBD1,
(BaseBlockDevice *) &SDCD1,
(BaseBlockDevice *) &SDLOG_SDIO,
USB_MS_DATA_EP,
&usbActivity,
"Pprz_sd",
@@ -134,7 +134,7 @@ static void thdUsbStorage(void *arg)
/* connect sdcard sdc interface sdio */
if (sdio_connect() == false) {
if (sdio_connect(&SDLOG_SDIO) == false) {
chThdExit(MSG_TIMEOUT);
}

View File

@@ -169,6 +169,12 @@ void _exit(int i) {
void _kill(void) {}
/***************************************************************************/
void __cxa_pure_virtual(void);
void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback
/***************************************************************************/
#endif // USE_CHIBIOS_RTOS
@@ -180,8 +186,6 @@ void _fini(void) {
}
void *__dso_handle;
void __cxa_pure_virtual(void);
void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback
#pragma GCC diagnostic pop

View File

@@ -0,0 +1,13 @@
{
"board_id": 53,
"magic": "PX4FWv1",
"description": "Firmware for the PX4FMUv6X board",
"image": "",
"build_time": 0,
"summary": "PX4FMUv6X",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}