mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
Merge first part of Pixhawk board support
First PR for getting Pixhawk to play nice with PPRZ. The Pixhawk can be flashed without external tools (i.e. no JTAG interface is needed). Instead, the PX4 bootloader is kept in place and used by pprz to flash both the AP (stm32f4) and FBW (stm32f1) devices. One important remark is that for the FBW device, currently the computer needs to be connected to the Telem2 port using a FTDI cable. This is because pprz does not support serial communication over USB, or so I've heard. In any case, the Iris+ drone factory equipped with a Pixhawk flies both on INDI and PID in ATT mode. However, PPRZ currently uses the MPU6000 IMU, which was broken in my Iris+ (and there are indications that maybe in others Iris' and X8's as well). I had to replace it with a fresh Pixhawk. Also tested with a Pixhawk clone: seems to work just as well. closes #1551
This commit is contained in:
@@ -154,6 +154,13 @@ upload: $(OBJDIR)/$(TARGET).bin
|
||||
@echo "Using ST-LINK with SWD at $(STLINK_ADDR)"
|
||||
$(Q)st-flash write $^ $(STLINK_ADDR)
|
||||
|
||||
else ifeq ($(FLASH_MODE),PX4_BOOTLOADER)
|
||||
# Program the device and start it.
|
||||
upload: $(OBJDIR)/$(TARGET).bin
|
||||
$(PAPARAZZI_SRC)/sw/tools/px4/px_mkfw.py --prototype $(PX4_PROTOTYPE) --image $(OBJDIR)/$(TARGET).bin > $(OBJDIR)/$(TARGET).px4
|
||||
$(PAPARAZZI_SRC)/sw/tools/px4/print_message.py
|
||||
$(PAPARAZZI_SRC)/sw/tools/px4/px_uploader.py --port $(PX4_BL_PORT) $(OBJDIR)/$(TARGET).px4
|
||||
|
||||
#
|
||||
# no known flash mode
|
||||
else
|
||||
|
||||
@@ -109,6 +109,17 @@
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/logger_sd_spi_direct.xml"
|
||||
gui_color="#9b69e5ce9e7a"
|
||||
/>
|
||||
<aircraft
|
||||
name="Iris"
|
||||
ac_id="66"
|
||||
airframe="airframes/TUDELFT/tudelft_iris_indi.xml"
|
||||
radio="radios/FrSky3dr.xml"
|
||||
telemetry="telemetry/default_rotorcraft_slow.xml"
|
||||
flight_plan="flight_plans/TUDELFT/tudelft_delft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml [settings/control/stabilization_att_int_quat.xml] settings/control/stabilization_indi.xml"
|
||||
settings_modules="modules/geo_mag.xml modules/air_data.xml modules/gps_ubx_ucenter.xml"
|
||||
gui_color="#ffffcccaccca"
|
||||
/>
|
||||
<aircraft
|
||||
name="Logo600"
|
||||
ac_id="111"
|
||||
|
||||
@@ -89,6 +89,16 @@
|
||||
<arg flag="-speech" />
|
||||
</program>
|
||||
</session>
|
||||
<session name="Flight Paparazzi @57600">
|
||||
<program name="Data Link">
|
||||
<arg flag="-d" constant="/dev/paparazzi/link"/>
|
||||
<arg flag="-s" constant="57600"/>
|
||||
</program>
|
||||
<program name="Server"/>
|
||||
<program name="GCS">
|
||||
<arg flag="-speech" />
|
||||
</program>
|
||||
</session>
|
||||
<session name="Flight ACM1 @57600">
|
||||
<program name="Data Link">
|
||||
<arg flag="-d" constant="/dev/ttyACM1"/>
|
||||
|
||||
@@ -0,0 +1,250 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!-- this is a quadrotor frame equiped with
|
||||
* Autopilot: 3dr Pixhawk 2.4
|
||||
* IMU: MPU6000 + L3GD20 + LSM303D
|
||||
* Actuators: PWM motor controllers?
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: PPM
|
||||
-->
|
||||
<airframe name="iris_indi">
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="px4fmu_2.4" />
|
||||
<define name="BAT_CHECKER_DELAY" value="80" />
|
||||
<!-- amount of time it take for the bat to check -->
|
||||
<!-- to avoid bat low spike detection when strong pullup withch draws short sudden power-->
|
||||
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
|
||||
<!-- in seconds-->
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim" />
|
||||
<subsystem name="udp" />
|
||||
</target>
|
||||
<subsystem name="telemetry" type="transparent" />
|
||||
<!-- <subsystem name="imu" type="px4fmu_v2.4">-->
|
||||
<subsystem name="imu" type="mpu6000">
|
||||
<configure name="IMU_MPU_SPI_DEV" value="spi1" />
|
||||
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE2" />
|
||||
</subsystem>
|
||||
<subsystem name="gps" type="ublox" />
|
||||
<subsystem name="stabilization" type="indi" />
|
||||
<subsystem name="ahrs" type="int_cmpl_quat" />
|
||||
<subsystem name="ins" type="extended" />
|
||||
<subsystem name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
|
||||
</subsystem>
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART6" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="rotorcraft">
|
||||
<target name="fbw" board="px4io_2.4" />
|
||||
<subsystem name="motor_mixing" />
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
|
||||
</subsystem>
|
||||
<!-- <subsystem name="radio_control" type="spektrum">-->
|
||||
<!-- <define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>-->
|
||||
<!-- <define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>-->
|
||||
<!-- <define name="RADIO_FBW_MODE" value="RADIO_AUX2"/>-->
|
||||
<!-- <define name="RADIO_MODE" value="RADIO_GEAR"/>-->
|
||||
<!-- <define name="SPEKTRUM_HAS_SOFT_BIND_PIN" value="1"/>-->
|
||||
<!-- </subsystem>-->
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400" />
|
||||
</subsystem>
|
||||
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
|
||||
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
|
||||
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
|
||||
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL" />
|
||||
<!-- Switch to Failsafe or to Manual on AP loss? -->
|
||||
<define name="INTERMCU_LOST_CNT" value="100" />
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART2" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_telemetry" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_baro_board" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_datalink" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<modules main_freq="512">
|
||||
<load name="px4io_flash.xml" />
|
||||
<load name="geo_mag.xml" />
|
||||
<load name="air_data.xml" />
|
||||
<load name="send_imu_mag_current.xml" />
|
||||
<load name="gps_ubx_ucenter.xml" />
|
||||
<!-- <load name="spektrum_soft_bind.xml"/>-->
|
||||
</modules>
|
||||
<section name="MISC">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)" />
|
||||
<!-- 100Amp = 2Volt -> 2482,42 tick/100Amp"(0.0402832*adc)" -->
|
||||
</section>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="14" />
|
||||
<define name="MAG_Y_NEUTRAL" value="116" />
|
||||
<define name="MAG_Z_NEUTRAL" value="119" />
|
||||
<define name="MAG_X_SENS" value="5.09245681612" integer="16" />
|
||||
<define name="MAG_Y_SENS" value="5.29702744632" integer="16" />
|
||||
<define name="MAG_Z_SENS" value="5.65287938992" integer="16" />
|
||||
<define name="BODY_TO_IMU_PHI" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_THETA" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_PSI" value="90." unit="deg" />
|
||||
</section>
|
||||
<commands>
|
||||
<axis name="PITCH" failsafe_value="0" />
|
||||
<axis name="ROLL" failsafe_value="0" />
|
||||
<axis name="YAW" failsafe_value="0" />
|
||||
<axis name="THRUST" failsafe_value="0" />
|
||||
</commands>
|
||||
<rc_commands>
|
||||
<set command="THRUST" value="@THROTTLE" />
|
||||
<set command="ROLL" value="@ROLL" />
|
||||
<set command="PITCH" value="@PITCH" />
|
||||
<set command="YAW" value="@YAW" />
|
||||
</rc_commands>
|
||||
<servos driver="Default">
|
||||
<servo name="TOP_LEFT" no="2" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="TOP_RIGHT" no="0" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_RIGHT" no="3" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_LEFT" no="1" min="1140" neutral="1280" max="1850" />
|
||||
</servos>
|
||||
<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="REVERSE" value="FALSE" />
|
||||
<define name="TYPE" value="QUAD_X" />
|
||||
</section>
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)" />
|
||||
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]" />
|
||||
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]" />
|
||||
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]" />
|
||||
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]" />
|
||||
</command_laws>
|
||||
<section name="AIR_DATA" prefix="AIR_DATA_">
|
||||
<define name="CALC_AIRSPEED" value="FALSE" />
|
||||
<define name="CALC_TAS_FACTOR" value="FALSE" />
|
||||
<define name="CALC_AMSL_BARO" value="TRUE" />
|
||||
</section>
|
||||
<!-- local magnetic field -->
|
||||
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
|
||||
<!-- Toulouse -->
|
||||
<!--define name="H_X" value="0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value="0.858336"/-->
|
||||
<!-- Delft -->
|
||||
<define name="H_X" value="0.3892503" />
|
||||
<define name="H_Y" value="0.0017972" />
|
||||
<define name="H_Z" value="0.9211303" />
|
||||
</section>
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="SONAR_MAX_RANGE" value="2.2" />
|
||||
<define name="SONAR_UPDATE_ON_AGL" value="TRUE" />
|
||||
</section>
|
||||
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoint limits for attitude stabilization rc flight -->
|
||||
<define name="SP_MAX_PHI" value="45" unit="deg" />
|
||||
<define name="SP_MAX_THETA" value="45" unit="deg" />
|
||||
<define name="SP_MAX_R" value="300" unit="deg/s" />
|
||||
<define name="DEADBAND_A" value="0" />
|
||||
<define name="DEADBAND_E" value="0" />
|
||||
<define name="DEADBAND_R" value="50" />
|
||||
</section>
|
||||
<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- attitude reference generation model -->
|
||||
<define name="REF_OMEGA_P" value="450" unit="deg/s" />
|
||||
<define name="REF_ZETA_P" value="0.9" />
|
||||
<define name="REF_MAX_P" value="600." unit="deg/s" />
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)" />
|
||||
<define name="REF_OMEGA_Q" value="450" unit="deg/s" />
|
||||
<define name="REF_ZETA_Q" value="0.9" />
|
||||
<define name="REF_MAX_Q" value="600." unit="deg/s" />
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)" />
|
||||
<define name="REF_OMEGA_R" value="450" unit="deg/s" />
|
||||
<define name="REF_ZETA_R" value="0.9" />
|
||||
<define name="REF_MAX_R" value="600." unit="deg/s" />
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)" />
|
||||
</section>
|
||||
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
|
||||
<!-- control effectiveness -->
|
||||
<define name="G1_P" value="0.017" />
|
||||
<define name="G1_Q" value="0.019" />
|
||||
<define name="G1_R" value="0.0011" />
|
||||
<define name="G2_R" value="0.089" />
|
||||
<!-- For the bebop2 we need to filter the roll rate due to the dampers -->
|
||||
<define name="FILTER_ROLL_RATE" value="FALSE" />
|
||||
<define name="FILTER_PITCH_RATE" value="FALSE" />
|
||||
<define name="FILTER_YAW_RATE" value="FALSE" />
|
||||
<!-- reference acceleration for attitude control -->
|
||||
<define name="REF_ERR_P" value="100.0" />
|
||||
<define name="REF_ERR_Q" value="100.0" />
|
||||
<define name="REF_ERR_R" value="100.0" />
|
||||
<define name="REF_RATE_P" value="14.0" />
|
||||
<define name="REF_RATE_Q" value="14.0" />
|
||||
<define name="REF_RATE_R" value="14.0" />
|
||||
<!-- second order filter parameters -->
|
||||
<define name="FILT_OMEGA" value="20.0" />
|
||||
<define name="FILT_ZETA" value="0.55" />
|
||||
<define name="FILT_OMEGA_R" value="20.0" />
|
||||
<define name="FILT_ZETA_R" value="0.55" />
|
||||
<!-- first order actuator dynamics -->
|
||||
<define name="ACT_DYN_P" value="0.04" />
|
||||
<define name="ACT_DYN_Q" value="0.04" />
|
||||
<define name="ACT_DYN_R" value="0.04" />
|
||||
<!-- 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="350" />
|
||||
<define name="HOVER_KD" value="85" />
|
||||
<define name="HOVER_KI" value="20" />
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.4" />
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE" />
|
||||
</section>
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<!-- Good weather -->
|
||||
<define name="MAX_BANK" value="20" unit="deg" />
|
||||
<define name="REF_MAX_SPEED" value="2" unit="m/s" />
|
||||
<!-- Bad weather -->
|
||||
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
|
||||
<define name="PGAIN" value="120" />
|
||||
<define name="DGAIN" value="100" />
|
||||
<define name="IGAIN" value="30" />
|
||||
</section>
|
||||
<section name="NAVIGATION" prefix="NAV_">
|
||||
<define name="CLIMB_VSPEED" value="4.5" />
|
||||
<define name="DESCEND_VSPEED" value="-1.0" />
|
||||
</section>
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]" />
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string" />
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string" />
|
||||
</section>
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_STARTUP" value="AP_MODE_RC_DIRECT" />
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT" /> <!-- changing this mode may not work, since fbw will be in mode manual directly from rc!-->
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="NO_RC_THRUST_LIMIT" value="TRUE" />
|
||||
</section>
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700" />
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V" />
|
||||
<define name="CRITIC_BAT_LEVEL" value="10.8" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="11.1" unit="V" />
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V" />
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -0,0 +1,230 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!-- this is a quadrotor frame equiped with
|
||||
* Autopilot: 3dr Pixhawk 2.4
|
||||
* IMU: MPU6000
|
||||
* Actuators: PWM motor controllers
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: PPM
|
||||
-->
|
||||
<airframe name="iris_pid">
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="px4fmu_2.4" />
|
||||
<define name="BAT_CHECKER_DELAY" value="80" />
|
||||
<!-- amount of time it take for the bat to check -->
|
||||
<!-- to avoid bat low spike detection when strong pullup withch draws short sudden power-->
|
||||
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="80" />
|
||||
<!-- in seconds-->
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim" />
|
||||
<subsystem name="udp" />
|
||||
</target>
|
||||
<subsystem name="telemetry" type="transparent" />
|
||||
<subsystem name="imu" type="mpu6000">
|
||||
<!-- <subsystem name="imu" type="L3GD20">-->
|
||||
<configure name="IMU_MPU_SPI_DEV" value="spi1" />
|
||||
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE2" />
|
||||
</subsystem>
|
||||
<subsystem name="gps" type="ublox" />
|
||||
<subsystem name="stabilization" type="int_quat" />
|
||||
<subsystem name="ahrs" type="int_cmpl_quat" />
|
||||
<subsystem name="ins" type="extended" />
|
||||
<subsystem name="current_sensor">
|
||||
<configure name="ADC_CURRENT_SENSOR" value="ADC_3" />
|
||||
</subsystem>
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART6" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="rotorcraft">
|
||||
<target name="fbw" board="px4io_2.4" />
|
||||
<subsystem name="motor_mixing" />
|
||||
<subsystem name="radio_control" type="ppm">
|
||||
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1" />
|
||||
<define name="RADIO_KILL_SWITCH" value="RADIO_KILL" />
|
||||
</subsystem>
|
||||
<!-- <subsystem name="radio_control" type="spektrum">-->
|
||||
<!-- <define name="RADIO_CONTROL_SPEKTRUM_NO_SIGN" value="1"/>-->
|
||||
<!-- <define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="1"/>-->
|
||||
<!-- <define name="RADIO_FBW_MODE" value="RADIO_AUX2"/>-->
|
||||
<!-- <define name="RADIO_MODE" value="RADIO_GEAR"/>-->
|
||||
<!-- <define name="SPEKTRUM_HAS_SOFT_BIND_PIN" value="1"/>-->
|
||||
<!-- </subsystem>-->
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400" />
|
||||
</subsystem>
|
||||
<define name="RC_LOST_FBW_MODE" value="FBW_MODE_FAILSAFE" />
|
||||
<!-- Switch to Failsafe or to Autopilot on RC loss? -->
|
||||
<define name="RC_LOST_IN_AUTO_FBW_MODE" value="FBW_MODE_AUTO" />
|
||||
<define name="AP_LOST_FBW_MODE" value="FBW_MODE_MANUAL" />
|
||||
<!-- Switch to Failsafe or to Manual on AP loss? -->
|
||||
<define name="INTERMCU_LOST_CNT" value="100" />
|
||||
<subsystem name="intermcu" type="uart">
|
||||
<configure name="INTERMCU_PORT" value="UART2" />
|
||||
<configure name="INTERMCU_BAUD" value="B1500000" />
|
||||
</subsystem>
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_telemetry" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_baro_board" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<firmware name="test_progs">
|
||||
<target name="test_datalink" board="px4fmu_2.4" />
|
||||
</firmware>
|
||||
<modules main_freq="512">
|
||||
<load name="px4io_flash.xml" />
|
||||
<load name="geo_mag.xml" />
|
||||
<load name="air_data.xml" />
|
||||
<load name="send_imu_mag_current.xml" />
|
||||
<load name="gps_ubx_ucenter.xml" />
|
||||
<!-- <load name="spektrum_soft_bind.xml"/>-->
|
||||
</modules>
|
||||
<section name="MISC">
|
||||
<define name="MilliAmpereOfAdc(adc)" value="((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)" />
|
||||
<!-- 100Amp = 2Volt -> 2482,42 tick/100Amp"(0.0402832*adc)" -->
|
||||
</section>
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="14" />
|
||||
<define name="MAG_Y_NEUTRAL" value="116" />
|
||||
<define name="MAG_Z_NEUTRAL" value="119" />
|
||||
<define name="MAG_X_SENS" value="5.09245681612" integer="16" />
|
||||
<define name="MAG_Y_SENS" value="5.29702744632" integer="16" />
|
||||
<define name="MAG_Z_SENS" value="5.65287938992" integer="16" />
|
||||
<define name="BODY_TO_IMU_PHI" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_THETA" value="180." unit="deg" />
|
||||
<define name="BODY_TO_IMU_PSI" value="90." unit="deg" />
|
||||
</section>
|
||||
<commands>
|
||||
<axis name="PITCH" failsafe_value="0" />
|
||||
<axis name="ROLL" failsafe_value="0" />
|
||||
<axis name="YAW" failsafe_value="0" />
|
||||
<axis name="THRUST" failsafe_value="0" />
|
||||
</commands>
|
||||
<rc_commands>
|
||||
<set command="THRUST" value="@THROTTLE" />
|
||||
<set command="ROLL" value="@ROLL" />
|
||||
<set command="PITCH" value="@PITCH" />
|
||||
<set command="YAW" value="@YAW" />
|
||||
</rc_commands>
|
||||
<servos driver="Default">
|
||||
<servo name="TOP_LEFT" no="2" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="TOP_RIGHT" no="0" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_RIGHT" no="3" min="1140" neutral="1280" max="1850" />
|
||||
<servo name="BOTTOM_LEFT" no="1" min="1140" neutral="1280" max="1850" />
|
||||
</servos>
|
||||
<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="REVERSE" value="FALSE" />
|
||||
<define name="TYPE" value="QUAD_X" />
|
||||
</section>
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)" />
|
||||
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]" />
|
||||
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]" />
|
||||
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]" />
|
||||
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]" />
|
||||
</command_laws>
|
||||
<section name="AIR_DATA" prefix="AIR_DATA_">
|
||||
<define name="CALC_AIRSPEED" value="FALSE" />
|
||||
<define name="CALC_TAS_FACTOR" value="FALSE" />
|
||||
<define name="CALC_AMSL_BARO" value="TRUE" />
|
||||
</section>
|
||||
<!-- local magnetic field -->
|
||||
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
|
||||
<!-- Toulouse -->
|
||||
<!--define name="H_X" value="0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value="0.858336"/-->
|
||||
<!-- Delft -->
|
||||
<define name="H_X" value="0.3892503" />
|
||||
<define name="H_Y" value="0.0017972" />
|
||||
<define name="H_Z" value="0.9211303" />
|
||||
</section>
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="SONAR_MAX_RANGE" value="2.2" />
|
||||
<define name="SONAR_UPDATE_ON_AGL" value="TRUE" />
|
||||
</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="HOVER_KP" value="350" />
|
||||
<define name="HOVER_KD" value="85" />
|
||||
<define name="HOVER_KI" value="20" />
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.4" />
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE" />
|
||||
</section>
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<!-- Good weather -->
|
||||
<define name="MAX_BANK" value="20" unit="deg" />
|
||||
<define name="REF_MAX_SPEED" value="2" unit="m/s" />
|
||||
<!-- Bad weather -->
|
||||
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
|
||||
<define name="PGAIN" value="120" />
|
||||
<define name="DGAIN" value="100" />
|
||||
<define name="IGAIN" value="30" />
|
||||
</section>
|
||||
<section name="NAVIGATION" prefix="NAV_">
|
||||
<define name="CLIMB_VSPEED" value="4.5" />
|
||||
<define name="DESCEND_VSPEED" value="-1.0" />
|
||||
</section>
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]" />
|
||||
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string" />
|
||||
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string" />
|
||||
</section>
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_STARTUP" value="AP_MODE_RC_DIRECT" />
|
||||
<define name="MODE_MANUAL" value="AP_MODE_RC_DIRECT" />
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_DIRECT" />
|
||||
<define name="NO_RC_THRUST_LIMIT" value="TRUE" />
|
||||
</section>
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700" />
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V" />
|
||||
<define name="CRITIC_BAT_LEVEL" value="10.8" unit="V" />
|
||||
<define name="LOW_BAT_LEVEL" value="11.1" unit="V" />
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V" />
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -2,7 +2,7 @@
|
||||
#
|
||||
# px4fmu_2.4.makefile
|
||||
#
|
||||
# This is for the main MCU (STM32F427) on the pixhawk board
|
||||
# This is for the main MCU (STM32F427) on the PX4 board
|
||||
# See https://pixhawk.org/modules/pixhawk for details
|
||||
#
|
||||
|
||||
@@ -19,10 +19,12 @@ $(TARGET).LDSCRIPT=$(SRC_ARCH)/px4fmu_2.4.ld
|
||||
|
||||
HARD_FLOAT=yes
|
||||
|
||||
# default flash mode is via usb dfu bootloader
|
||||
# possibilities: DFU, SWD
|
||||
FLASH_MODE ?= SWD
|
||||
|
||||
# default flash mode is the PX4 bootloader
|
||||
# possibilities: DFU, SWD, PX4 bootloader
|
||||
FLASH_MODE ?= PX4_BOOTLOADER
|
||||
PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/px4fmu-v2.prototype"
|
||||
PX4_BL_PORT ?= "/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/pci-3D_Robotics*"
|
||||
$(TARGET).MAKEFILE = stm32
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
@@ -40,12 +42,10 @@ SYS_TIME_LED ?= 1
|
||||
MODEM_PORT ?= UART2
|
||||
MODEM_BAUD ?= B57600
|
||||
|
||||
#The GPS serial on px4 is called serial 3, but connected to uart4 on the f4
|
||||
GPS_PORT ?= UART4
|
||||
GPS_BAUD ?= B38400
|
||||
|
||||
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2
|
||||
|
||||
|
||||
#
|
||||
# default actuator configuration
|
||||
#
|
||||
|
||||
@@ -0,0 +1,48 @@
|
||||
# Hey Emacs, this is a -*- makefile -*-
|
||||
#
|
||||
# px4io_2.4.makefile
|
||||
#
|
||||
# This is for the main MCU (STM32F427) on the PX4 board
|
||||
# See https://pixhawk.org/modules/pixhawk for details
|
||||
#
|
||||
|
||||
BOARD=px4io
|
||||
BOARD_VERSION=2.4
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
|
||||
ARCH=stm32
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
$(TARGET).LDSCRIPT=$(SRC_ARCH)/px4io_2.4.ld
|
||||
|
||||
# default flash mode is via usb dfu bootloader
|
||||
# possibilities: DFU, SWD, PX4_BOOTLOADER
|
||||
PX4_BL_PORT ?= "/dev/serial/by-id/usb-FTDI_*"
|
||||
PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/px4io-v2.prototype"
|
||||
|
||||
FLASH_MODE ?= PX4_BOOTLOADER
|
||||
$(TARGET).MAKEFILE = stm32
|
||||
|
||||
#
|
||||
# default LED configuration
|
||||
#
|
||||
RADIO_CONTROL_LED ?= none
|
||||
BARO_LED ?= none
|
||||
AHRS_ALIGNER_LED ?= none
|
||||
GPS_LED ?= none
|
||||
SYS_TIME_LED ?= 1
|
||||
FBW_MODE_LED ?= 3
|
||||
|
||||
#
|
||||
# default UART configuration (modem, gps, spektrum)
|
||||
#
|
||||
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART1
|
||||
|
||||
#
|
||||
# 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
|
||||
@@ -11,6 +11,7 @@ ifeq ($(TARGET),fbw)
|
||||
INTERMCU_PORT ?= UART2
|
||||
INTERMCU_PORT_LOWER = $(shell echo $(INTERMCU_PORT) | tr A-Z a-z)
|
||||
fbw.CFLAGS += -DINTERMCU_LINK=$(INTERMCU_PORT_LOWER) -DUSE_$(INTERMCU_PORT) -D$(INTERMCU_PORT)_BAUD=B57600
|
||||
fbw.CFLAGS += -DFBW_MODE_LED=$(FBW_MODE_LED)
|
||||
else
|
||||
INTERMCU_PORT ?= UART5
|
||||
INTERMCU_PORT_LOWER = $(shell echo $(INTERMCU_PORT) | tr A-Z a-z)
|
||||
|
||||
@@ -4,18 +4,24 @@
|
||||
|
||||
ifeq ($(TARGET),fbw)
|
||||
INTERMCU_PORT ?= UART3
|
||||
INTERMCU_BAUD ?= B230400
|
||||
INTERMCU_PORT_LOWER = $(shell echo $(INTERMCU_PORT) | tr A-Z a-z)
|
||||
fbw.CFLAGS += -DINTERMCU_LINK=$(INTERMCU_PORT_LOWER) -DUSE_$(INTERMCU_PORT) -D$(INTERMCU_PORT)_BAUD=B230400
|
||||
fbw.CFLAGS += -DINTERMCU_LINK=$(INTERMCU_PORT_LOWER) -DUSE_$(INTERMCU_PORT) -D$(INTERMCU_PORT)_BAUD=$(INTERMCU_BAUD)
|
||||
fbw.CFLAGS += -DINTER_MCU_FBW -DDOWNLINK
|
||||
fbw.CFLAGS += -DFBW_MODE_LED=$(FBW_MODE_LED)
|
||||
fbw.srcs += pprzlink/src/pprz_transport.c
|
||||
fbw.srcs += subsystems/intermcu/intermcu_fbw.c
|
||||
else
|
||||
INTERMCU_PORT ?= UART3
|
||||
INTERMCU_BAUD ?= B230400
|
||||
INTERMCU_PORT_LOWER = $(shell echo $(INTERMCU_PORT) | tr A-Z a-z)
|
||||
ap.CFLAGS += -DINTER_MCU_AP -DINTERMCU_LINK=$(INTERMCU_PORT_LOWER)
|
||||
ap.CFLAGS += -DUSE_$(INTERMCU_PORT) -D$(INTERMCU_PORT)_BAUD=B230400
|
||||
ap.CFLAGS += -DUSE_$(INTERMCU_PORT) -D$(INTERMCU_PORT)_BAUD=$(INTERMCU_BAUD)
|
||||
$(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/intermcu/intermcu_ap.h\" -DRADIO_CONTROL
|
||||
$(TARGET).CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED)
|
||||
RADIO_CONTROL_LED ?= none
|
||||
ifneq ($(RADIO_CONTROL_LED),none)
|
||||
$(TARGET).CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED)
|
||||
endif
|
||||
|
||||
ap.srcs += subsystems/intermcu/intermcu_ap.c
|
||||
ap.srcs += pprzlink/src/pprz_transport.c
|
||||
|
||||
@@ -167,8 +167,8 @@ else ifeq ($(BOARD), krooz)
|
||||
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c
|
||||
|
||||
# PX4FMU
|
||||
else ifeq ($(BOARD), px4fmu)
|
||||
BARO_BOARD_CFLAGS += -DUSE_I2C2
|
||||
else ifeq ($(BOARD),$(filter $(BOARD),px4fmu))
|
||||
BARO_BOARD_CFLAGS += -DUSE_I2C2
|
||||
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2
|
||||
BARO_BOARD_SRCS += peripherals/ms5611.c
|
||||
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
|
||||
|
||||
@@ -229,6 +229,23 @@ test_telemetry.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_telemetry.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_telemetry.srcs += test/test_telemetry.c
|
||||
|
||||
#
|
||||
# test_datalink : Sends ALIVE and pong telemetry messages
|
||||
#
|
||||
# configuration
|
||||
# MODEM_PORT :
|
||||
# MODEM_BAUD :
|
||||
#
|
||||
test_datalink.ARCHDIR = $(ARCH)
|
||||
test_datalink.CFLAGS += $(COMMON_TEST_CFLAGS)
|
||||
test_datalink.srcs += $(COMMON_TEST_SRCS)
|
||||
test_datalink.CFLAGS += $(COMMON_DATALINK_CFLAGS)
|
||||
test_datalink.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
||||
test_datalink.srcs += $(COMMON_DATALINK_SRCS)
|
||||
test_datalink.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||
test_datalink.srcs += test/test_datalink.c
|
||||
|
||||
|
||||
#
|
||||
# test_math_trig_compressed: Test math trigonometric using compressed data
|
||||
#
|
||||
|
||||
@@ -96,6 +96,13 @@
|
||||
<board name="px4fmu_.*"/>
|
||||
<board name="elle*"/>
|
||||
</boards>
|
||||
</mode>
|
||||
<mode name="Px4 bootloader">
|
||||
<variable name="FLASH_MODE" value="PX4_BOOTLOADER"/>
|
||||
<boards>
|
||||
<board name="px4fmu_.*"/>
|
||||
<board name="px4io_.*"/>
|
||||
</boards>
|
||||
</mode>
|
||||
<mode name="JTAG (OpenOCD)">
|
||||
<variable name="FLASH_MODE" value="JTAG"/>
|
||||
|
||||
@@ -0,0 +1,31 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="px4io_flash">
|
||||
<doc>
|
||||
<description>Flashes the px4io f1 through the px4 bootloader.</description>
|
||||
</doc>
|
||||
<header>
|
||||
<file name="px4io_flash.h"/>
|
||||
</header>
|
||||
<init fun="px4ioflash_init()"/>
|
||||
<event fun="px4ioflash_event()"/>
|
||||
<makefile target="ap">
|
||||
<raw>
|
||||
|
||||
</raw>
|
||||
<file name="px4io_flash.c"/>
|
||||
<configure name="PX4IO_UART" default="uart6" case="upper|lower"/>
|
||||
<configure name="PX4IO_BAUD" default="B1500000"/>
|
||||
<define name="USE_$(PX4IO_UART_UPPER)"/>
|
||||
<define name="PX4IO_UART" value="$(PX4IO_UART_LOWER)"/>
|
||||
<define name="$(PX4IO_UART_UPPER)_BAUD" value="$(PX4IO_BAUD)"/>
|
||||
|
||||
<configure name="TELEM2_UART" default="uart3" case="upper|lower"/>
|
||||
<configure name="TELEM2_BAUD" default="B115200"/>
|
||||
<define name="USE_$(TELEM2_UART_UPPER)"/>
|
||||
<define name="TELEM2_UART" value="$(TELEM2_UART_LOWER)"/>
|
||||
<define name="$(TELEM2_UART_UPPER)_BAUD" value="$(TELEM2_BAUD)"/>
|
||||
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
@@ -0,0 +1,25 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="spektrum_soft_bind" dir="spektrum_soft_bind">
|
||||
<doc>
|
||||
<description>Puts Spektrum in binding mode through software</description>
|
||||
</doc>
|
||||
<settings target="ap">
|
||||
<dl_settings>
|
||||
<dl_settings name="Spektrum soft bind">
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="bind_soft_value" values="FALSE|TRUE" shortname="Bind Spektrum" module="spektrum_soft_bind/spektrum_soft_bind" handler="click"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
<header >
|
||||
<file name="spektrum_soft_bind.h"/>
|
||||
</header>
|
||||
<init fun="spektrum_soft_bind_init()"/>
|
||||
<makefile target="ap">
|
||||
<file name="spektrum_soft_bind_ap.c"/>
|
||||
</makefile>
|
||||
<makefile target="fbw">
|
||||
<file name="spektrum_soft_bind_fbw.c"/>
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
@@ -0,0 +1,60 @@
|
||||
<?xml version="1.0"?>
|
||||
<!-- $Id$
|
||||
--
|
||||
-- (c) 2006 Pascal Brisset, Antoine Drouin
|
||||
--
|
||||
-- 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.
|
||||
-->
|
||||
|
||||
<!--
|
||||
-- Attributes of root (Radio) tag :
|
||||
-- name: name of RC
|
||||
-- data_min: min width of a pulse to be considered as a data pulse
|
||||
-- data_max: max width of a pulse to be considered as a data pulse
|
||||
-- sync_min: min width of a pulse to be considered as a synchro pulse
|
||||
-- sync_max: max width of a pulse to be considered as a synchro pulse
|
||||
-- pulse_type: POSITIVE ( Futaba and others) | NEGATIVE (JR)
|
||||
-- min, max and sync are expressed in micro-seconds
|
||||
-->
|
||||
|
||||
<!--
|
||||
-- Attributes of channel tag :
|
||||
-- ctl: name of the command on the transmitter - only for displaying
|
||||
-- function: logical command
|
||||
-- average: (boolean) channel filtered through several frames (for discrete commands)
|
||||
-- min: minimum pulse length (micro-seconds)
|
||||
-- max: maximum pulse length (micro-seconds)
|
||||
-- neutral: neutral pulse length (micro-seconds)
|
||||
-- Note: a command may be reversed by exchanging min and max values
|
||||
-->
|
||||
|
||||
<!DOCTYPE radio SYSTEM "radio.dtd">
|
||||
|
||||
<!-- Values set by experiment using X8R receiver SBus connection -->
|
||||
|
||||
<radio name="FrSky X9D + X8R receiver SBus connection" data_min="350" data_max="2500" sync_min ="8000" sync_max ="19000" pulse_type="POSITIVE">
|
||||
<channel ctl="D" function="ROLL" min="990" neutral="1490" max="2015" average="0"/>
|
||||
<channel ctl="C" function="PITCH" min="990" neutral="1490" max="2015" average="0"/>
|
||||
<channel ctl="A" function="THROTTLE" min="990" neutral="990" max="2015" average="0"/>
|
||||
<channel ctl="B" function="YAW" min="990" neutral="1490" max="2015" average="0"/>
|
||||
|
||||
<channel ctl="RSwtiches_Mix" function="MODE" min="1145" neutral="1500" max="1862" average="1"/>
|
||||
<channel ctl="TILT" function="AUX2" min="990" neutral="990" max="2015" average="0"/>
|
||||
<channel ctl="CH7" function="KILL" min="990" neutral="1490" max="2015" average="1"/>
|
||||
<channel ctl="E" function="UNUSED2" min="990" neutral="1900" max="2015" average="1"/>
|
||||
</radio>
|
||||
@@ -20,6 +20,9 @@ SUBSYSTEM=="tty", ATTRS{product}=="FT232R USB UART", SYMLINK+="ftdi-serial", GRO
|
||||
# Paparazzi STM32 Autopilot board USB CDC serial device
|
||||
SUBSYSTEM=="tty", ATTRS{manufacturer}=="Paparazzi UAV", ATTRS{product}=="CDC Serial STM32", SYMLINK+="paparazzi/stm32-usb-serial"
|
||||
|
||||
# Paparazzi 3dr radio
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6015", SYMLINK+="paparazzi/link", GROUP="plugdev"
|
||||
|
||||
# MaxStream xbee pro box
|
||||
SUBSYSTEM=="tty", ATTRS{product}=="MaxStream PKG-U", SYMLINK+="paparazzi/xbee", GROUP="plugdev"
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
<?xml version="1.0"?>
|
||||
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
|
||||
<!DOCTYPE telemetry SYSTEM "../telemetry.dtd">
|
||||
<telemetry>
|
||||
<process name="Ap">
|
||||
<mode name="default">
|
||||
|
||||
@@ -27,7 +27,8 @@
|
||||
<message name="AIR_DATA" period="2.3"/>
|
||||
<message name="SURVEY" period="4.5"/>
|
||||
<message name="OPTIC_FLOW_EST" period="0.5"/>
|
||||
<message name="VECTORNAV_INFO" period="0.5"/>
|
||||
<message name="VECTORNAV_INFO" period="0.5"/>
|
||||
<message name="FBW_STATUS" period="2"/>
|
||||
</mode>
|
||||
|
||||
<mode name="ppm">
|
||||
|
||||
@@ -42,50 +42,115 @@
|
||||
#if defined(STM32F4)
|
||||
/* untested, should go into libopencm3 */
|
||||
const clock_scale_t hse_24mhz_3v3[CLOCK_3V3_END] = {
|
||||
{ /* 48MHz */
|
||||
.pllm = 24,
|
||||
.plln = 96,
|
||||
.pllp = 2,
|
||||
.pllq = 2,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.power_save = 1,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_3WS,
|
||||
.apb1_frequency = 12000000,
|
||||
.apb2_frequency = 24000000,
|
||||
},
|
||||
{ /* 120MHz */
|
||||
.pllm = 24,
|
||||
.plln = 240,
|
||||
.pllp = 2,
|
||||
.pllq = 5,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.power_save = 1,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_3WS,
|
||||
.apb1_frequency = 30000000,
|
||||
.apb2_frequency = 60000000,
|
||||
},
|
||||
{ /* 168MHz */
|
||||
.pllm = 24,
|
||||
.plln = 336,
|
||||
.pllp = 2,
|
||||
.pllq = 7,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_5WS,
|
||||
.apb1_frequency = 42000000,
|
||||
.apb2_frequency = 84000000,
|
||||
},
|
||||
{ /* 48MHz */
|
||||
.pllm = 24,
|
||||
.plln = 96,
|
||||
.pllp = 2,
|
||||
.pllq = 2,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.power_save = 1,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_3WS,
|
||||
.apb1_frequency = 12000000,
|
||||
.apb2_frequency = 24000000,
|
||||
},
|
||||
{ /* 120MHz */
|
||||
.pllm = 24,
|
||||
.plln = 240,
|
||||
.pllp = 2,
|
||||
.pllq = 5,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.power_save = 1,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_3WS,
|
||||
.apb1_frequency = 30000000,
|
||||
.apb2_frequency = 60000000,
|
||||
},
|
||||
{ /* 168MHz */
|
||||
.pllm = 24,
|
||||
.plln = 336,
|
||||
.pllp = 2,
|
||||
.pllq = 7,
|
||||
.hpre = RCC_CFGR_HPRE_DIV_NONE,
|
||||
.ppre1 = RCC_CFGR_PPRE_DIV_4,
|
||||
.ppre2 = RCC_CFGR_PPRE_DIV_2,
|
||||
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
|
||||
FLASH_ACR_LATENCY_5WS,
|
||||
.apb1_frequency = 42000000,
|
||||
.apb2_frequency = 84000000,
|
||||
},
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(STM32F1)
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @brief RCC Set System Clock HSE at 24MHz from HSE at 24MHz
|
||||
|
||||
*/
|
||||
void rcc_clock_setup_in_hse_24mhz_out_24mhz_pprz(void);
|
||||
void rcc_clock_setup_in_hse_24mhz_out_24mhz_pprz(void)
|
||||
{
|
||||
/* Enable internal high-speed oscillator. */
|
||||
rcc_osc_on(HSI);
|
||||
rcc_wait_for_osc_ready(HSI);
|
||||
|
||||
/* Select HSI as SYSCLK source. */
|
||||
rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
|
||||
|
||||
/* Enable external high-speed oscillator 24MHz. */
|
||||
rcc_osc_on(HSE);
|
||||
rcc_wait_for_osc_ready(HSE);
|
||||
rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSECLK);
|
||||
|
||||
/*
|
||||
* Set prescalers for AHB, ADC, ABP1, ABP2.
|
||||
* Do this before touching the PLL (TODO: why?).
|
||||
*/
|
||||
rcc_set_hpre(RCC_CFGR_HPRE_SYSCLK_NODIV); /* Set. 24MHz Max. 72MHz */
|
||||
rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV2); /* Set. 12MHz Max. 14MHz */
|
||||
rcc_set_ppre1(RCC_CFGR_PPRE1_HCLK_NODIV); /* Set. 24MHz Max. 36MHz */
|
||||
rcc_set_ppre2(RCC_CFGR_PPRE2_HCLK_NODIV); /* Set. 24MHz Max. 72MHz */
|
||||
|
||||
/*
|
||||
* Sysclk runs with 24MHz -> 0 waitstates.
|
||||
* 0WS from 0-24MHz
|
||||
* 1WS from 24-48MHz
|
||||
* 2WS from 48-72MHz
|
||||
*/
|
||||
flash_set_ws(FLASH_ACR_LATENCY_0WS);
|
||||
|
||||
/*
|
||||
* Set the PLL multiplication factor to 2.
|
||||
* 24MHz (external) * 2 (multiplier) / 2 (RCC_CFGR_PLLXTPRE_HSE_CLK_DIV2) = 24MHz
|
||||
*/
|
||||
rcc_set_pll_multiplication_factor(RCC_CFGR_PLLMUL_PLL_CLK_MUL2);
|
||||
|
||||
/* Select HSE as PLL source. */
|
||||
rcc_set_pll_source(RCC_CFGR_PLLSRC_HSE_CLK);
|
||||
|
||||
/*
|
||||
* External frequency divide by 2 before entering PLL
|
||||
* (only valid/needed for HSE).
|
||||
*/
|
||||
rcc_set_pllxtpre(RCC_CFGR_PLLXTPRE_HSE_CLK_DIV2);
|
||||
|
||||
rcc_osc_on(PLL);
|
||||
rcc_wait_for_osc_ready(PLL);
|
||||
|
||||
/* Select PLL as SYSCLK source. */
|
||||
rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_PLLCLK);
|
||||
|
||||
/* Set the peripheral clock frequencies used */
|
||||
rcc_ahb_frequency = 24000000;
|
||||
rcc_apb1_frequency = 24000000;
|
||||
rcc_apb2_frequency = 24000000;
|
||||
}
|
||||
#endif
|
||||
|
||||
void mcu_arch_init(void)
|
||||
{
|
||||
#if LUFTBOOT
|
||||
@@ -121,6 +186,8 @@ void mcu_arch_init(void)
|
||||
#if defined(STM32F4)
|
||||
PRINT_CONFIG_MSG("Using 24MHz external clock to PLL it to 168MHz.")
|
||||
rcc_clock_setup_hse_3v3(&hse_24mhz_3v3[CLOCK_3V3_168MHZ]);
|
||||
#elif defined(STM32F1)
|
||||
rcc_clock_setup_in_hse_24mhz_out_24mhz_pprz();
|
||||
#endif
|
||||
#elif EXT_CLK == 25000000
|
||||
#if defined(STM32F4)
|
||||
@@ -142,6 +209,7 @@ void mcu_arch_init(void)
|
||||
}
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
||||
#define RCC_CFGR_PPRE2_SHIFT 11
|
||||
#define RCC_CFGR_PPRE2 (7 << RCC_CFGR_PPRE2_SHIFT)
|
||||
|
||||
@@ -191,8 +259,7 @@ uint32_t timer_get_frequency(uint32_t timer_peripheral)
|
||||
#ifdef TIM11
|
||||
case TIM11:
|
||||
#endif
|
||||
if (!rcc_get_ppre2())
|
||||
{
|
||||
if (!rcc_get_ppre2()) {
|
||||
/* without APB2 prescaler, runs at APB2 freq */
|
||||
return rcc_apb2_frequency;
|
||||
} else {
|
||||
@@ -216,8 +283,7 @@ uint32_t timer_get_frequency(uint32_t timer_peripheral)
|
||||
#ifdef TIM14
|
||||
case TIM14:
|
||||
#endif
|
||||
if (!rcc_get_ppre1())
|
||||
{
|
||||
if (!rcc_get_ppre1()) {
|
||||
/* without APB1 prescaler, runs at APB1 freq */
|
||||
return rcc_apb1_frequency;
|
||||
} else {
|
||||
|
||||
@@ -147,7 +147,7 @@ PRINT_CONFIG_MSG("Analog to Digital Coverter 2 active")
|
||||
#if USE_AD3
|
||||
PRINT_CONFIG_MSG("Analog to Digital Coverter 3 active")
|
||||
#endif
|
||||
#if !USE_AD1 && !USE_AD2 && !USE_AD3
|
||||
#if !USE_AD1 && !USE_AD2 && !USE_AD3 && !defined FBW
|
||||
#warning ALL ADC CONVERTERS INACTIVE
|
||||
#endif
|
||||
|
||||
@@ -222,11 +222,12 @@ static struct {
|
||||
|
||||
void adc_init(void)
|
||||
{
|
||||
|
||||
#if USE_AD1 || USE_AD2 || USE_AD3
|
||||
uint8_t x = 0;
|
||||
|
||||
// ADC channel mapping
|
||||
uint8_t adc_channel_map[4];
|
||||
#endif
|
||||
|
||||
/* Init GPIO ports for ADC operation
|
||||
*/
|
||||
@@ -582,9 +583,11 @@ void adc1_2_isr(void)
|
||||
void adc_isr(void)
|
||||
#endif
|
||||
{
|
||||
#if USE_AD1 || USE_AD2 || USE_AD3
|
||||
uint8_t channel = 0;
|
||||
uint16_t value = 0;
|
||||
struct adc_buf *buf;
|
||||
#endif
|
||||
|
||||
#if USE_ADC_WATCHDOG
|
||||
/*
|
||||
|
||||
@@ -40,6 +40,7 @@
|
||||
#define B115200 115200
|
||||
#define B230400 230400
|
||||
#define B921600 921600
|
||||
#define B1500000 1500000
|
||||
#define UART_SPEED(_def) _def
|
||||
|
||||
#endif /* STM32_UART_ARCH_H */
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Felix Ruess
|
||||
* Copyright (C) 2016 The Paparazzi Team>
|
||||
*
|
||||
* This file is part of Paparazzi.
|
||||
*
|
||||
@@ -19,15 +19,14 @@
|
||||
* Boston, MA 02111-1307, USA.
|
||||
*/
|
||||
|
||||
/* Linker script for Pixhawk PX4FMU v2.4 (STM32F427, 2048K flash, 256K RAM). */
|
||||
/* Linker script for Pixhawk PX4FMU v2.4 (STM32F427, 1024K flash, 192K RAM). */
|
||||
|
||||
/* Define memory regions. */
|
||||
MEMORY
|
||||
{
|
||||
/* only 192K (SRAM1 and SRAM2) are accessible by all AHB masters. */
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
/* Reserving 128kb flash for persistent settings. */
|
||||
rom (rx) : ORIGIN = 0x08000000, LENGTH = 1920K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
/* Pixhawk seems to have had a bad badge of f4's, so only use the first 1mb */
|
||||
rom (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
|
||||
}
|
||||
|
||||
/* Include the common ld script. */
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
/*
|
||||
* Hey Emacs, this is a -*- makefile -*-
|
||||
*
|
||||
* Copyright (C) 2016 Kevin van Hecke
|
||||
*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/* Linker script for the PX4IO (STM32F103c8t6 medium density, 64 Kbytes Flash). */
|
||||
|
||||
/* Define memory regions. */
|
||||
MEMORY
|
||||
{
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
|
||||
/* Leaving 2k of space at the end of rom for stored settings */
|
||||
rom (rx) : ORIGIN = 0x08001000, LENGTH = 60K
|
||||
}
|
||||
|
||||
/* Include the common ld script. */
|
||||
INCLUDE libopencm3_stm32f1.ld
|
||||
|
||||
@@ -43,7 +43,6 @@ int32_t actuators_pwm_values[ACTUATORS_PWM_NB];
|
||||
*/
|
||||
void actuators_pwm_arch_init(void)
|
||||
{
|
||||
|
||||
/*-----------------------------------
|
||||
* Configure timer peripheral clocks
|
||||
*-----------------------------------*/
|
||||
|
||||
@@ -56,14 +56,55 @@ INFO("Radio-Control now follows PPRZ sign convention: this means you might need
|
||||
#define MIN_FRAME_SPACE 70 // 7ms
|
||||
#define MAX_BYTE_SPACE 3 // .3ms
|
||||
|
||||
|
||||
//not all f1's have a timer 6, so, some redefines have to happen
|
||||
#define PASTER3(x,y,z) x ## y ## z
|
||||
#define EVALUATOR3(x,y,z) PASTER3(x,y,z)
|
||||
#define NVIC_TIMx_IRQ EVALUATOR3(NVIC_TIM, SPEKTRUM_TIMER,_IRQ)
|
||||
#define NVIC_TIMx_DAC_IRQ EVALUATOR3(NVIC_TIM, SPEKTRUM_TIMER,_DAC_IRQ) // not really necessary, only for f4 which probably always has a timer 4
|
||||
#define TIMx_ISR EVALUATOR3(tim, SPEKTRUM_TIMER,_isr)
|
||||
#define TIMx_DAC_ISR EVALUATOR3(tim, SPEKTRUM_TIMER,_dac_isr)
|
||||
|
||||
#define PASTER2(x,y) x ## y
|
||||
#define EVALUATOR2(x,y) PASTER2(x,y)
|
||||
#define TIMx EVALUATOR2(TIM, SPEKTRUM_TIMER)
|
||||
#define RCC_TIMx EVALUATOR2(RCC_TIM, SPEKTRUM_TIMER)
|
||||
|
||||
#ifndef SPEKTRUM_TIMER
|
||||
#define SPEKTRUM_TIMER 6
|
||||
#endif
|
||||
|
||||
#if (SPEKTRUM_TIMER == 6)
|
||||
#ifndef NVIC_TIM6_IRQ_PRIO
|
||||
#define NVIC_TIM6_IRQ_PRIO 2
|
||||
#define NVIC_TIMx_IRQ_PRIO 2
|
||||
#else
|
||||
#define NVIC_TIMx_IRQ_PRIO NVIC_TIM6_IRQ_PRIO
|
||||
#endif
|
||||
|
||||
#ifndef NVIC_TIM6_DAC_IRQ_PRIO
|
||||
#define NVIC_TIM6_DAC_IRQ_PRIO 2
|
||||
#define NVIC_TIMx_DAC_IRQ_PRIO 2
|
||||
#else
|
||||
#define NVIC_TIMx_DAC_IRQ_PRIO NVIC_TIM6_DAC_IRQ_PRIO
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if (SPEKTRUM_TIMER == 3)
|
||||
#ifndef NVIC_TIM3_IRQ_PRIO
|
||||
#define NVIC_TIM3_IRQ_PRIO 2
|
||||
#define NVIC_TIMx_IRQ_PRIO 2
|
||||
#else
|
||||
#define NVIC_TIMx_IRQ_PRIO NVIC_TIM6_IRQ_PRIO
|
||||
#endif
|
||||
#ifndef NVIC_TIM3_DAC_IRQ_PRIO
|
||||
#define NVIC_TIM3_DAC_IRQ_PRIO 2
|
||||
#define NVIC_TIMx_DAC_IRQ_PRIO 2
|
||||
#else
|
||||
#define NVIC_TIMx_DAC_IRQ_PRIO NVIC_TIM6_DAC_IRQ_PRIO
|
||||
#endif
|
||||
#endif
|
||||
|
||||
PRINT_CONFIG_MSG_VALUE("SPEKTRUM_TIMER: " , SPEKTRUM_TIMER)
|
||||
|
||||
#ifdef NVIC_UART_IRQ_PRIO
|
||||
#define NVIC_PRIMARY_UART_PRIO NVIC_UART_IRQ_PRIO
|
||||
@@ -136,13 +177,10 @@ int8_t SpektrumSigns[] = RADIO_CONTROL_SPEKTRUM_SIGNS;
|
||||
/* Parser state variables */
|
||||
static uint8_t EncodingType = 0;
|
||||
static uint8_t ExpectedFrames = 0;
|
||||
/* initialise the uarts used by the parser */
|
||||
void SpektrumUartInit(void);
|
||||
|
||||
/* initialise the timer used by the parser to ensure sync */
|
||||
void SpektrumTimerInit(void);
|
||||
|
||||
void tim6_irq_handler(void);
|
||||
|
||||
/** Set polarity using RC_POLARITY_GPIO.
|
||||
* SBUS signal has a reversed polarity compared to normal UART
|
||||
* this allows to using hardware UART peripheral by changing
|
||||
@@ -289,6 +327,8 @@ void radio_control_impl_init(void)
|
||||
static inline void SpektrumParser(uint8_t _c, SpektrumStateType *spektrum_state, bool_t secondary_receiver)
|
||||
{
|
||||
|
||||
|
||||
|
||||
uint16_t ChannelData;
|
||||
uint8_t TimedOut;
|
||||
static uint8_t TmpEncType = 0; /* 0 = 10bit, 1 = 11 bit */
|
||||
@@ -299,7 +339,7 @@ static inline void SpektrumParser(uint8_t _c, SpektrumStateType *spektrum_state,
|
||||
/* If we have just started the resync process or */
|
||||
/* if we have recieved a character before our */
|
||||
/* 7ms wait has finished */
|
||||
if ((spektrum_state->ReSync == 1) ||
|
||||
if ((spektrum_state->ReSync == 1) ||
|
||||
((spektrum_state->Sync == 0) && (!TimedOut))) {
|
||||
|
||||
spektrum_state->ReSync = 0;
|
||||
@@ -310,6 +350,7 @@ static inline void SpektrumParser(uint8_t _c, SpektrumStateType *spektrum_state,
|
||||
spektrum_state->SecondFrame = 0;
|
||||
return;
|
||||
}
|
||||
//LED_OFF(1);
|
||||
|
||||
/* the first byte of a new frame. It was received */
|
||||
/* more than 7ms after the last received byte. */
|
||||
@@ -503,55 +544,56 @@ void RadioControlEventImp(void (*frame_handler)(void))
|
||||
|
||||
/*****************************************************************************
|
||||
*
|
||||
* Initialise TIM6 to fire an interrupt every 100 microseconds to provide
|
||||
* Initialise TIMx to fire an interrupt every 100 microseconds to provide
|
||||
* timebase for SpektrumParser
|
||||
*
|
||||
*****************************************************************************/
|
||||
void SpektrumTimerInit(void)
|
||||
{
|
||||
|
||||
/* enable TIM6 clock */
|
||||
rcc_periph_clock_enable(RCC_TIM6);
|
||||
/* enable TIMx clock */
|
||||
rcc_periph_clock_enable(RCC_TIMx);
|
||||
|
||||
/* TIM6 configuration, always counts up */
|
||||
timer_set_mode(TIM6, TIM_CR1_CKD_CK_INT, 0, 0);
|
||||
timer_reset(TIMx);
|
||||
/* TIMx configuration, always counts up */
|
||||
timer_set_mode(TIMx, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // used to be 0 0
|
||||
/* 100 microseconds ie 0.1 millisecond */
|
||||
timer_set_period(TIM6, TIM_TICS_FOR_100us - 1);
|
||||
uint32_t tim6_clk = timer_get_frequency(TIM6);
|
||||
timer_set_period(TIMx, TIM_TICS_FOR_100us - 1);
|
||||
uint32_t TIMx_clk = timer_get_frequency(TIMx);
|
||||
/* timer ticks with 1us */
|
||||
timer_set_prescaler(TIM6, ((tim6_clk / ONE_MHZ) - 1));
|
||||
timer_set_prescaler(TIMx, ((TIMx_clk / ONE_MHZ) - 1));
|
||||
|
||||
/* Enable TIM6 interrupts */
|
||||
/* Enable TIMx interrupts */
|
||||
#ifdef STM32F1
|
||||
nvic_set_priority(NVIC_TIM6_IRQ, NVIC_TIM6_IRQ_PRIO);
|
||||
nvic_enable_irq(NVIC_TIM6_IRQ);
|
||||
nvic_set_priority(NVIC_TIMx_IRQ, NVIC_TIMx_IRQ_PRIO);
|
||||
nvic_enable_irq(NVIC_TIMx_IRQ);
|
||||
#elif defined STM32F4
|
||||
/* the define says DAC IRQ, but it is also the global TIM6 IRQ*/
|
||||
nvic_set_priority(NVIC_TIM6_DAC_IRQ, NVIC_TIM6_DAC_IRQ_PRIO);
|
||||
nvic_enable_irq(NVIC_TIM6_DAC_IRQ);
|
||||
/* the define says DAC IRQ, but it is also the global TIMx IRQ*/
|
||||
nvic_set_priority(NVIC_TIMx_DAC_IRQ, NVIC_TIMx_DAC_IRQ_PRIO);
|
||||
nvic_enable_irq(NVIC_TIMx_DAC_IRQ);
|
||||
#endif
|
||||
|
||||
/* Enable TIM6 Update interrupt */
|
||||
timer_enable_irq(TIM6, TIM_DIER_UIE);
|
||||
timer_clear_flag(TIM6, TIM_SR_UIF);
|
||||
/* Enable TIMx Update interrupt */
|
||||
timer_enable_irq(TIMx, TIM_DIER_UIE);
|
||||
timer_clear_flag(TIMx, TIM_SR_UIF);
|
||||
|
||||
/* TIM6 enable counter */
|
||||
timer_enable_counter(TIM6);
|
||||
/* TIMx enable counter */
|
||||
timer_enable_counter(TIMx);
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
*
|
||||
* TIM6 interrupt request handler updates times used by SpektrumParser
|
||||
* TIMx interrupt request handler updates times used by SpektrumParser
|
||||
*
|
||||
*****************************************************************************/
|
||||
#ifdef STM32F1
|
||||
void tim6_isr(void)
|
||||
void TIMx_ISR(void)
|
||||
{
|
||||
#elif defined STM32F4
|
||||
void tim6_dac_isr(void) {
|
||||
void TIMx_DAC_ISR(void) {
|
||||
#endif
|
||||
|
||||
timer_clear_flag(TIM6, TIM_SR_UIF);
|
||||
timer_clear_flag(TIMx, TIM_SR_UIF);
|
||||
|
||||
if (PrimarySpektrumState.SpektrumTimer) {
|
||||
--PrimarySpektrumState.SpektrumTimer;
|
||||
@@ -582,7 +624,7 @@ void SpektrumUartInit(void) {
|
||||
gpio_setup_pin_af(PrimaryUart(_BANK), PrimaryUart(_PIN), PrimaryUart(_AF), FALSE);
|
||||
|
||||
/* Configure Primary UART */
|
||||
usart_set_baudrate(PrimaryUart(_DEV), 115200);
|
||||
usart_set_baudrate(PrimaryUart(_DEV), B115200);
|
||||
usart_set_databits(PrimaryUart(_DEV), 8);
|
||||
usart_set_stopbits(PrimaryUart(_DEV), USART_STOPBITS_1);
|
||||
usart_set_parity(PrimaryUart(_DEV), USART_PARITY_NONE);
|
||||
@@ -609,7 +651,7 @@ void SpektrumUartInit(void) {
|
||||
gpio_setup_pin_af(SecondaryUart(_BANK), SecondaryUart(_PIN), SecondaryUart(_AF), FALSE);
|
||||
|
||||
/* Configure secondary UART */
|
||||
usart_set_baudrate(SecondaryUart(_DEV), 115200);
|
||||
usart_set_baudrate(SecondaryUart(_DEV), B115200);
|
||||
usart_set_databits(SecondaryUart(_DEV), 8);
|
||||
usart_set_stopbits(SecondaryUart(_DEV), USART_STOPBITS_1);
|
||||
usart_set_parity(SecondaryUart(_DEV), USART_PARITY_NONE);
|
||||
@@ -701,7 +743,7 @@ void SecondaryUart(_ISR)(void) {
|
||||
*
|
||||
*****************************************************************************/
|
||||
void radio_control_spektrum_try_bind(void) {
|
||||
|
||||
#ifdef SPEKTRUM_BIND_PIN_PORT
|
||||
#ifdef SPEKTRUM_BIND_PIN_HIGH
|
||||
/* Init GPIO for the bind pin, we enable the pulldown resistor.
|
||||
* (esden) As far as I can tell only navstick is using the PIN LOW version of
|
||||
@@ -727,6 +769,7 @@ void radio_control_spektrum_try_bind(void) {
|
||||
if (gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) != 0) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* Master receiver Rx push-pull */
|
||||
|
||||
@@ -79,5 +79,7 @@
|
||||
#endif
|
||||
|
||||
extern void RadioControlEventImp(void (*_received_frame_handler)(void));
|
||||
/* initialise the uarts used by the parser */
|
||||
void SpektrumUartInit(void);
|
||||
|
||||
#endif /* RADIO_CONTROL_SPEKTRUM_ARCH_H */
|
||||
|
||||
@@ -4,14 +4,14 @@
|
||||
#define BOARD_PX4FMU_v2
|
||||
|
||||
/* Pixhawk board (PX4FMUv2 has a 24MHz external clock and 168MHz internal. */
|
||||
//STM32F4
|
||||
#define EXT_CLK 24000000
|
||||
#define AHB_CLK 168000000
|
||||
|
||||
|
||||
/*
|
||||
* Onboard LEDs
|
||||
*/
|
||||
/* red/amber , on PE12 */
|
||||
/* red, on PE12 */
|
||||
#ifndef USE_LED_1
|
||||
#define USE_LED_1 1
|
||||
#endif
|
||||
@@ -23,13 +23,6 @@
|
||||
|
||||
/*
|
||||
* UART
|
||||
*/
|
||||
/*
|
||||
#define UART1_GPIO_AF GPIO_AF7
|
||||
#define UART1_GPIO_PORT_RX GPIOA
|
||||
#define UART1_GPIO_RX GPIO9
|
||||
#define UART1_GPIO_PORT_TX GPIOA
|
||||
#define UART1_GPIO_TX GPIO10
|
||||
*/
|
||||
|
||||
//OK // conector telem1
|
||||
@@ -156,24 +149,19 @@
|
||||
// SDIO_CMD pd2
|
||||
|
||||
/* Onboard ADCs */
|
||||
#define USE_AD_TIM4 1
|
||||
|
||||
#define BOARD_ADC_CHANNEL_1 11
|
||||
#define BOARD_ADC_CHANNEL_2 12
|
||||
#define BOARD_ADC_CHANNEL_3 13
|
||||
#define BOARD_ADC_CHANNEL_4 10
|
||||
#define USE_AD_TIM5 1
|
||||
|
||||
/* provide defines that can be used to access the ADC_x in the code or airframe file
|
||||
* these directly map to the index number of the 4 adc channels defined above
|
||||
* 4th (index 3) is used for bat monitoring by default
|
||||
*/
|
||||
|
||||
#if USE_ADC_1
|
||||
#define AD1_1_CHANNEL 11
|
||||
#define ADC_1 AD1_1
|
||||
#define ADC_1_GPIO_PORT GPIOC
|
||||
#define ADC_1_GPIO_PIN GPIO1
|
||||
#endif
|
||||
//#if USE_ADC_1
|
||||
//#define AD1_1_CHANNEL 11
|
||||
//#define ADC_1 AD1_1
|
||||
//#define ADC_1_GPIO_PORT GPIOC
|
||||
//#define ADC_1_GPIO_PIN GPIO1
|
||||
//#endif
|
||||
/*
|
||||
#if USE_ADC_2
|
||||
#define AD1_2_CHANNEL 12
|
||||
@@ -185,18 +173,19 @@
|
||||
|
||||
//OK current sens
|
||||
#if USE_ADC_3
|
||||
#define AD1_3_CHANNEL 13
|
||||
#define AD1_3_CHANNEL 3
|
||||
#define ADC_3 AD1_3
|
||||
#define ADC_3_GPIO_PORT GPIOA
|
||||
#define ADC_3_GPIO_PIN GPIO3
|
||||
#endif
|
||||
#define MilliAmpereOfAdc(adc)((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)
|
||||
|
||||
// Internal ADC for battery enabled by default
|
||||
#ifndef USE_ADC_4
|
||||
#define USE_ADC_4 1
|
||||
#endif
|
||||
#if USE_ADC_4
|
||||
#define AD1_4_CHANNEL 10
|
||||
#define AD1_4_CHANNEL 2
|
||||
#define ADC_4 AD1_4
|
||||
#define ADC_4_GPIO_PORT GPIOA
|
||||
#define ADC_4_GPIO_PIN GPIO2
|
||||
@@ -206,7 +195,7 @@
|
||||
#ifndef ADC_CHANNEL_VSUPPLY
|
||||
#define ADC_CHANNEL_VSUPPLY ADC_4
|
||||
#endif
|
||||
#define DefaultVoltageOfAdc(adc) (0.006185*adc)
|
||||
#define DefaultVoltageOfAdc(adc) (0.00975f*adc) // value comes from px4 code sensors.cpp _parameters.battery_voltage_scaling = 0.0082f; Manual calib on iris = 0.0096...
|
||||
|
||||
|
||||
/*
|
||||
@@ -229,45 +218,6 @@
|
||||
#define I2C3_GPIO_SDA GPIO9
|
||||
*/
|
||||
|
||||
/*
|
||||
* PPM
|
||||
*/
|
||||
|
||||
|
||||
#define USE_PPM_TIM1 1
|
||||
|
||||
#define PPM_CHANNEL TIM_IC1
|
||||
#define PPM_TIMER_INPUT TIM_IC_IN_TI1
|
||||
#define PPM_IRQ NVIC_TIM1_CC_IRQ
|
||||
#define PPM_IRQ2 NVIC_TIM1_UP_TIM10_IRQ
|
||||
// Capture/Compare InteruptEnable and InterruptFlag
|
||||
#define PPM_CC_IE TIM_DIER_CC1IE
|
||||
#define PPM_CC_IF TIM_SR_CC1IF
|
||||
#define PPM_GPIO_PORT GPIOA
|
||||
#define PPM_GPIO_PIN GPIO10
|
||||
#define PPM_GPIO_AF GPIO_AF1
|
||||
|
||||
/*
|
||||
* Spektrum
|
||||
*/
|
||||
/* The line that is pulled low at power up to initiate the bind process */
|
||||
/* GPIO_EXT1 on PX4FMU */
|
||||
|
||||
/*
|
||||
#define SPEKTRUM_BIND_PIN GPIO4
|
||||
#define SPEKTRUM_BIND_PIN_PORT GPIOC
|
||||
*/
|
||||
/*
|
||||
#define SPEKTRUM_UART2_RCC RCC_USART2
|
||||
#define SPEKTRUM_UART2_BANK GPIOA
|
||||
#define SPEKTRUM_UART2_PIN GPIO3
|
||||
#define SPEKTRUM_UART2_AF GPIO_AF7
|
||||
#define SPEKTRUM_UART2_IRQ NVIC_USART2_IRQ
|
||||
#define SPEKTRUM_UART2_ISR usart2_isr
|
||||
#define SPEKTRUM_UART2_DEV USART2
|
||||
*/
|
||||
|
||||
|
||||
/* Activate onboard baro by default */
|
||||
#ifndef USE_BARO_BOARD
|
||||
#define USE_BARO_BOARD 1
|
||||
@@ -290,6 +240,7 @@
|
||||
#define USE_PWM4 1
|
||||
#define USE_PWM5 1
|
||||
#define USE_PWM6 1
|
||||
//#define USE_BUZZER 1
|
||||
|
||||
// Servo numbering on the PX4 starts with 1
|
||||
// PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
|
||||
@@ -372,8 +323,7 @@
|
||||
#define PWM_SERVO_6_OC_BIT 0
|
||||
#endif
|
||||
|
||||
//Buzzer
|
||||
/*
|
||||
//Buzzer (alarm)
|
||||
#if USE_BUZZER
|
||||
#define PWM_BUZZER
|
||||
#define PWM_BUZZER_TIMER TIM2
|
||||
@@ -385,11 +335,9 @@
|
||||
#else
|
||||
#define PWM_BUZZER_OC_BIT 0
|
||||
#endif
|
||||
*/
|
||||
|
||||
|
||||
#define PWM_TIM1_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT)
|
||||
//#define PWM_TIM2_CHAN_MASK (PWM_BUZZER_OC_BIT)
|
||||
#define PWM_TIM2_CHAN_MASK (PWM_BUZZER_OC_BIT)
|
||||
#define PWM_TIM4_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT)
|
||||
|
||||
#endif /* CONFIG_PX4FMU_2_4_H */
|
||||
|
||||
@@ -0,0 +1,243 @@
|
||||
#ifndef CONFIG_PX4IO_2_4_H
|
||||
#define CONFIG_PX4IO_2_4_H
|
||||
|
||||
#define BOARD_PX4IO
|
||||
//STM32F103c8t6 (medium density!)
|
||||
|
||||
/* Pixhawk board (PX4FIOv2 has a 24MHz external clock and 24MHz internal. */
|
||||
#define EXT_CLK 24000000 //this osc is actually outside of the specs (max 16MHz)
|
||||
#define AHB_CLK 24000000
|
||||
|
||||
|
||||
/*
|
||||
* LEDs
|
||||
*/
|
||||
/* blue led, a.k.a. ACT */
|
||||
#ifndef USE_LED_1
|
||||
#define USE_LED_1 1
|
||||
#endif
|
||||
#define LED_1_GPIO GPIOB
|
||||
#define LED_1_GPIO_PIN GPIO14
|
||||
#define LED_1_GPIO_ON gpio_clear
|
||||
#define LED_1_GPIO_OFF gpio_set
|
||||
#define LED_1_AFIO_REMAP ((void)0)
|
||||
|
||||
//led Amber a.k.a b/e led
|
||||
#ifndef USE_LED_2
|
||||
#define USE_LED_2 1
|
||||
#endif
|
||||
#define LED_2_GPIO GPIOB
|
||||
#define LED_2_GPIO_PIN GPIO15
|
||||
#define LED_2_GPIO_ON gpio_clear
|
||||
#define LED_2_GPIO_OFF gpio_set
|
||||
#define LED_2_AFIO_REMAP ((void)0)
|
||||
|
||||
//safety led in the switch, red
|
||||
#ifndef USE_LED_3
|
||||
#define USE_LED_3 1
|
||||
#endif
|
||||
#define LED_3_GPIO GPIOB
|
||||
#define LED_3_GPIO_PIN GPIO13
|
||||
#define LED_3_GPIO_ON gpio_clear
|
||||
#define LED_3_GPIO_OFF gpio_set
|
||||
#define LED_3_AFIO_REMAP ((void)0)
|
||||
|
||||
//TODO: safety switch is on PB5!
|
||||
|
||||
/*
|
||||
* UART
|
||||
*/
|
||||
|
||||
// fmu debug / spektrum receiver (only rx)
|
||||
#define UART1_GPIO_AF 0
|
||||
#define UART1_GPIO_PORT_RX GPIOA
|
||||
#define UART1_GPIO_RX GPIO10
|
||||
#define UART1_GPIO_PORT_TX GPIOA
|
||||
#define UART1_GPIO_TX GPIO9
|
||||
// intermcu fmu
|
||||
#define UART2_GPIO_AF 0
|
||||
#define UART2_GPIO_PORT_RX GPIOA
|
||||
#define UART2_GPIO_RX GPIO3
|
||||
#define UART2_GPIO_PORT_TX GPIOA
|
||||
#define UART2_GPIO_TX GPIO2
|
||||
|
||||
|
||||
/*
|
||||
* Spektrum
|
||||
*/
|
||||
/* The line that is pulled low at power up to initiate the bind process */
|
||||
#define SPEKTRUM_POWER_PIN_PORT GPIOC
|
||||
#define SPEKTRUM_POWER_PIN GPIO13
|
||||
|
||||
#define SPEKTRUM_TIMER 3
|
||||
|
||||
#define SPEKTRUM_UART1_RCC RCC_USART1
|
||||
#define SPEKTRUM_UART1_BANK GPIOA
|
||||
#define SPEKTRUM_UART1_PIN GPIO10
|
||||
#define SPEKTRUM_UART1_AF 0
|
||||
#define SPEKTRUM_UART1_IRQ NVIC_USART1_IRQ
|
||||
#define SPEKTRUM_UART1_ISR usart1_isr
|
||||
#define SPEKTRUM_UART1_DEV USART1
|
||||
|
||||
|
||||
/*
|
||||
* PPM input
|
||||
*/
|
||||
#define USE_PPM_TIM1 1
|
||||
#define PPM_CHANNEL TIM_IC1
|
||||
#define PPM_TIMER_INPUT TIM_IC_IN_TI1
|
||||
#define PPM_IRQ NVIC_TIM1_UP_IRQ
|
||||
#define PPM_IRQ2 NVIC_TIM1_CC_IRQ
|
||||
// Capture/Compare InteruptEnable and InterruptFlag
|
||||
#define PPM_CC_IE TIM_DIER_CC1IE
|
||||
#define PPM_CC_IF TIM_SR_CC1IF
|
||||
#define PPM_GPIO_PORT GPIOA
|
||||
#define PPM_GPIO_PIN GPIO8
|
||||
#define PPM_GPIO_AF 0
|
||||
|
||||
//#define USE_AD_TIM1 1
|
||||
#ifndef USE_ADC_1
|
||||
#define USE_ADC_1 0
|
||||
#endif
|
||||
#if USE_ADC_1 // VDD servo ADC12_IN4, untested
|
||||
#define AD1_1_CHANNEL 12
|
||||
#define ADC_1 AD1_4
|
||||
#define ADC_1_GPIO_PORT GPIOA
|
||||
#define ADC_1_GPIO_PIN GPIO4
|
||||
#endif
|
||||
|
||||
/*
|
||||
* PWM
|
||||
*
|
||||
*/
|
||||
//sevo outputs on px4io f1:
|
||||
//chn: 1 2 3 4 5 6 7 8
|
||||
//pin: A0 A1 B8 B9 A6 A7 B0 B1
|
||||
//timer/channel: 2/1 2/2 4/3 4/4 3/1 3/2 3/3 3/4
|
||||
#define PWM_USE_TIM2 1
|
||||
//#define PWM_USE_TIM3 1 // spektrum already uses tim3
|
||||
#define PWM_USE_TIM4 1
|
||||
|
||||
//#define ACTUATORS_PWM_NB 4
|
||||
|
||||
#define USE_PWM1 1
|
||||
#define USE_PWM2 1
|
||||
#define USE_PWM3 1
|
||||
#define USE_PWM4 1
|
||||
//#define USE_PWM5 1
|
||||
//#define USE_PWM6 1
|
||||
//#define USE_PWM7 1
|
||||
//#define USE_PWM8 1
|
||||
|
||||
// PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
|
||||
#if USE_PWM1
|
||||
#define PWM_SERVO_1 0
|
||||
#define PWM_SERVO_1_TIMER TIM2
|
||||
#define PWM_SERVO_1_GPIO GPIOA
|
||||
#define PWM_SERVO_1_PIN GPIO0
|
||||
#define PWM_SERVO_1_AF 0
|
||||
#define PWM_SERVO_1_OC TIM_OC1
|
||||
#define PWM_SERVO_1_OC_BIT (1<<0)
|
||||
#else
|
||||
#define PWM_SERVO_1_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM2
|
||||
#define PWM_SERVO_2 1
|
||||
#define PWM_SERVO_2_TIMER TIM2
|
||||
#define PWM_SERVO_2_GPIO GPIOA
|
||||
#define PWM_SERVO_2_PIN GPIO1
|
||||
#define PWM_SERVO_2_AF 0
|
||||
#define PWM_SERVO_2_OC TIM_OC2
|
||||
#define PWM_SERVO_2_OC_BIT (1<<1)
|
||||
#else
|
||||
#define PWM_SERVO_2_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM3
|
||||
#define PWM_SERVO_3 2
|
||||
#define PWM_SERVO_3_TIMER TIM4
|
||||
#define PWM_SERVO_3_GPIO GPIOB
|
||||
#define PWM_SERVO_3_PIN GPIO8
|
||||
#define PWM_SERVO_3_AF 0
|
||||
#define PWM_SERVO_3_OC TIM_OC3
|
||||
#define PWM_SERVO_3_OC_BIT (1<<2)
|
||||
#else
|
||||
#define PWM_SERVO_3_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM4
|
||||
#define PWM_SERVO_4 3
|
||||
#define PWM_SERVO_4_TIMER TIM4
|
||||
#define PWM_SERVO_4_GPIO GPIOB
|
||||
#define PWM_SERVO_4_PIN GPIO9
|
||||
#define PWM_SERVO_4_AF 0
|
||||
#define PWM_SERVO_4_OC TIM_OC4
|
||||
#define PWM_SERVO_4_OC_BIT (1<<3)
|
||||
#else
|
||||
#define PWM_SERVO_4_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM5
|
||||
#define PWM_SERVO_5 4
|
||||
#define PWM_SERVO_5_TIMER TIM3
|
||||
#define PWM_SERVO_5_GPIO GPIOA
|
||||
#define PWM_SERVO_5_PIN GPIO6
|
||||
#define PWM_SERVO_5_AF 0
|
||||
#define PWM_SERVO_5_OC TIM_OC1
|
||||
#define PWM_SERVO_5_OC_BIT (1<<0)
|
||||
#else
|
||||
#define PWM_SERVO_5_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM6
|
||||
#define PWM_SERVO_6 5
|
||||
#define PWM_SERVO_6_TIMER TIM3
|
||||
#define PWM_SERVO_6_GPIO GPIOA
|
||||
#define PWM_SERVO_6_PIN GPIO7
|
||||
#define PWM_SERVO_6_AF 0
|
||||
#define PWM_SERVO_6_OC TIM_OC2
|
||||
#define PWM_SERVO_6_OC_BIT (1<<1)
|
||||
#else
|
||||
#define PWM_SERVO_6_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM7
|
||||
#define PWM_SERVO_7 6
|
||||
#define PWM_SERVO_7_TIMER TIM3
|
||||
#define PWM_SERVO_7_GPIO GPIOB
|
||||
#define PWM_SERVO_7_PIN GPIO0
|
||||
#define PWM_SERVO_7_AF 0
|
||||
#define PWM_SERVO_7_OC TIM_OC3
|
||||
#define PWM_SERVO_7_OC_BIT (1<<2)
|
||||
#else
|
||||
#define PWM_SERVO_7_OC_BIT 0
|
||||
#endif
|
||||
|
||||
#if USE_PWM8
|
||||
#define PWM_SERVO_8 7
|
||||
#define PWM_SERVO_8_TIMER TIM3
|
||||
#define PWM_SERVO_8_GPIO GPIOB
|
||||
#define PWM_SERVO_8_PIN GPIO1
|
||||
#define PWM_SERVO_8_AF 0
|
||||
#define PWM_SERVO_8_OC TIM_OC4
|
||||
#define PWM_SERVO_8_OC_BIT (1<<3)
|
||||
#else
|
||||
#define PWM_SERVO_8_OC_BIT 0
|
||||
#endif
|
||||
|
||||
/* servos 1-2 on TIM2 */
|
||||
#define PWM_TIM2_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT)
|
||||
/* servos 3-4 on TIM4 */
|
||||
#define PWM_TIM4_CHAN_MASK (PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT)
|
||||
/* servos 5-8 on TIM3 */
|
||||
//#define PWM_TIM3_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT|PWM_SERVO_7_OC_BIT|PWM_SERVO_8_OC_BIT)
|
||||
|
||||
/* Default actuators driver */
|
||||
#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
|
||||
#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
|
||||
#define ActuatorsDefaultInit() ActuatorsPwmInit()
|
||||
#define ActuatorsDefaultCommit() ActuatorsPwmCommit()
|
||||
|
||||
|
||||
#endif /* CONFIG_PX4IO_2_4_H */
|
||||
@@ -47,7 +47,8 @@
|
||||
#include "firmwares/rotorcraft/main_fbw.h"
|
||||
#include "firmwares/rotorcraft/autopilot_rc_helpers.h"
|
||||
|
||||
//#include "generated/modules.h"
|
||||
#define MODULES_C
|
||||
#include "generated/modules.h"
|
||||
|
||||
/** Fly by wire modes */
|
||||
typedef enum {FBW_MODE_MANUAL = 0, FBW_MODE_AUTO = 1, FBW_MODE_FAILSAFE = 2} fbw_mode_enum;
|
||||
@@ -59,7 +60,7 @@ fbw_mode_enum fbw_mode;
|
||||
//PRINT_CONFIG_VAR(MODULES_FREQUENCY)
|
||||
|
||||
tid_t main_periodic_tid; ///< id for main_periodic() timer
|
||||
//tid_t modules_tid; ///< id for modules_periodic_task() timer
|
||||
tid_t modules_tid; ///< id for modules_periodic_task() timer
|
||||
tid_t radio_control_tid; ///< id for radio_control_periodic_task() timer
|
||||
tid_t electrical_tid; ///< id for electrical_periodic() timer
|
||||
tid_t telemetry_tid; ///< id for telemetry_periodic() timer
|
||||
@@ -85,17 +86,17 @@ STATIC_INLINE void main_init(void)
|
||||
|
||||
mcu_init();
|
||||
|
||||
actuators_init();
|
||||
|
||||
electrical_init();
|
||||
|
||||
actuators_init();
|
||||
#if USE_MOTOR_MIXING
|
||||
motor_mixing_init();
|
||||
#endif
|
||||
|
||||
radio_control_init();
|
||||
|
||||
// TODO
|
||||
//modules_init();
|
||||
modules_init();
|
||||
|
||||
mcu_int_enable();
|
||||
|
||||
@@ -103,7 +104,7 @@ STATIC_INLINE void main_init(void)
|
||||
|
||||
// register the timers for the periodic functions
|
||||
main_periodic_tid = sys_time_register_timer((1. / PERIODIC_FREQUENCY), NULL);
|
||||
// modules_tid = sys_time_register_timer(1. / MODULES_FREQUENCY, NULL);
|
||||
modules_tid = sys_time_register_timer(1. / MODULES_FREQUENCY, NULL);
|
||||
radio_control_tid = sys_time_register_timer((1. / 60.), NULL);
|
||||
electrical_tid = sys_time_register_timer(0.1, NULL);
|
||||
telemetry_tid = sys_time_register_timer((1. / 20.), NULL);
|
||||
@@ -115,13 +116,15 @@ STATIC_INLINE void main_init(void)
|
||||
|
||||
STATIC_INLINE void handle_periodic_tasks(void)
|
||||
{
|
||||
|
||||
|
||||
if (sys_time_check_and_ack_timer(main_periodic_tid)) {
|
||||
main_periodic();
|
||||
}
|
||||
//if (sys_time_check_and_ack_timer(modules_tid)) {
|
||||
// TODO
|
||||
//modules_periodic_task();
|
||||
//}
|
||||
if (sys_time_check_and_ack_timer(modules_tid)) {
|
||||
|
||||
modules_periodic_task();
|
||||
}
|
||||
if (sys_time_check_and_ack_timer(radio_control_tid)) {
|
||||
radio_control_periodic_task();
|
||||
}
|
||||
@@ -175,9 +178,17 @@ STATIC_INLINE void main_periodic(void)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static uint16_t dv = 0;
|
||||
// TODO make module out of led blink?
|
||||
/* set failsafe commands */
|
||||
if (fbw_mode == FBW_MODE_FAILSAFE) {
|
||||
SetCommands(commands_failsafe);
|
||||
if (!(dv++ % (PERIODIC_FREQUENCY / 20))) { LED_TOGGLE(FBW_MODE_LED);}
|
||||
} else if (fbw_mode == FBW_MODE_MANUAL) {
|
||||
if (!(dv++ % (PERIODIC_FREQUENCY))) { LED_TOGGLE(FBW_MODE_LED);}
|
||||
} else if (fbw_mode == FBW_MODE_AUTO) {
|
||||
LED_TOGGLE(FBW_MODE_LED); // toggle instead of on, because then it is still visible when fbw_mode switches very fast
|
||||
}
|
||||
|
||||
/* set actuators */
|
||||
@@ -208,6 +219,7 @@ static void autopilot_on_rc_frame(void)
|
||||
|
||||
/* if manual */
|
||||
if (fbw_mode == FBW_MODE_MANUAL) {
|
||||
autopilot_motors_on = TRUE;
|
||||
#ifdef SetCommandsFromRC
|
||||
SetCommandsFromRC(commands, radio_control.values);
|
||||
#else
|
||||
@@ -216,13 +228,15 @@ static void autopilot_on_rc_frame(void)
|
||||
}
|
||||
|
||||
/* Forward radiocontrol to AP */
|
||||
intermcu_on_rc_frame();
|
||||
intermcu_on_rc_frame(fbw_mode);
|
||||
}
|
||||
|
||||
static void autopilot_on_ap_command(void)
|
||||
{
|
||||
if (fbw_mode != FBW_MODE_MANUAL) {
|
||||
SetCommands(intermcu_commands);
|
||||
} else {
|
||||
autopilot_motors_on = TRUE;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -237,6 +251,6 @@ STATIC_INLINE void main_event(void)
|
||||
// InterMCU
|
||||
InterMcuEvent(autopilot_on_ap_command);
|
||||
|
||||
// TODO Modules
|
||||
//modules_event_task();
|
||||
//Modules
|
||||
modules_event_task();
|
||||
}
|
||||
|
||||
+1
-1
@@ -83,7 +83,7 @@ void mcu_init(void)
|
||||
led_init();
|
||||
#endif
|
||||
/* for now this means using spektrum */
|
||||
#if defined RADIO_CONTROL & defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT & defined RADIO_CONTROL_BIND_IMPL_FUNC
|
||||
#if defined RADIO_CONTROL & defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT & defined RADIO_CONTROL_BIND_IMPL_FUNC & defined SPEKTRUM_BIND_PIN_PORT
|
||||
RADIO_CONTROL_BIND_IMPL_FUNC();
|
||||
#endif
|
||||
#if USE_UART0
|
||||
|
||||
@@ -66,7 +66,7 @@ struct uart_periph {
|
||||
uint8_t tx_buf[UART_TX_BUFFER_SIZE];
|
||||
uint16_t tx_insert_idx;
|
||||
uint16_t tx_extract_idx;
|
||||
uint8_t tx_running;
|
||||
volatile uint8_t tx_running;
|
||||
/** UART Register */
|
||||
void *reg_addr;
|
||||
/** UART Baudrate */
|
||||
|
||||
@@ -0,0 +1,390 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define __STDC_FORMAT_MACROS
|
||||
#include "std.h"
|
||||
|
||||
/**
|
||||
* @file protocol.h
|
||||
*
|
||||
* PX4IO interface protocol.
|
||||
*
|
||||
* Communication is performed via writes to and reads from 16-bit virtual
|
||||
* registers organised into pages of 255 registers each.
|
||||
*
|
||||
* The first two bytes of each write select a page and offset address
|
||||
* respectively. Subsequent reads and writes increment the offset within
|
||||
* the page.
|
||||
*
|
||||
* Some pages are read- or write-only.
|
||||
*
|
||||
* Note that some pages may permit offset values greater than 255, which
|
||||
* can only be achieved by long writes. The offset does not wrap.
|
||||
*
|
||||
* Writes to unimplemented registers are ignored. Reads from unimplemented
|
||||
* registers return undefined values.
|
||||
*
|
||||
* As convention, values that would be floating point in other parts of
|
||||
* the PX4 system are expressed as signed integer values scaled by 10000,
|
||||
* e.g. control values range from -10000..10000. Use the REG_TO_SIGNED and
|
||||
* SIGNED_TO_REG macros to convert between register representation and
|
||||
* the signed version, and REG_TO_FLOAT/FLOAT_TO_REG to convert to float.
|
||||
*
|
||||
* Note that the implementation of readable pages prefers registers within
|
||||
* readable pages to be densely packed. Page numbers do not need to be
|
||||
* packed.
|
||||
*
|
||||
* Definitions marked [1] are only valid on PX4IOv1 boards. Likewise,
|
||||
* [2] denotes definitions specific to the PX4IOv2 board.
|
||||
*/
|
||||
|
||||
/* Per C, this is safe for all 2's complement systems */
|
||||
#define REG_TO_SIGNED(_reg) ((int16_t)(_reg))
|
||||
#define SIGNED_TO_REG(_signed) ((uint16_t)(_signed))
|
||||
|
||||
#define REG_TO_FLOAT(_reg) ((float)REG_TO_SIGNED(_reg) / 10000.0f)
|
||||
#define FLOAT_TO_REG(_float) SIGNED_TO_REG((int16_t)((_float) * 10000.0f))
|
||||
|
||||
#define PX4IO_PROTOCOL_VERSION 4
|
||||
|
||||
/* maximum allowable sizes on this protocol version */
|
||||
#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT 8 /**< The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT */
|
||||
|
||||
/* static configuration page */
|
||||
#define PX4IO_PAGE_CONFIG 0
|
||||
#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* PX4IO_PROTOCOL_VERSION */
|
||||
#define PX4IO_P_CONFIG_HARDWARE_VERSION 1 /* magic numbers TBD */
|
||||
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */
|
||||
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
|
||||
#define PX4IO_P_CONFIG_CONTROL_COUNT 4 /* hardcoded max control count supported */
|
||||
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
|
||||
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
|
||||
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
|
||||
#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
|
||||
#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT 8 /**< hardcoded # of control groups*/
|
||||
|
||||
/* dynamic status page */
|
||||
#define PX4IO_PAGE_STATUS 1
|
||||
#define PX4IO_P_STATUS_FREEMEM 0
|
||||
#define PX4IO_P_STATUS_CPULOAD 1
|
||||
|
||||
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */
|
||||
#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */
|
||||
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 4) /* DSM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 5) /* SBUS input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 6) /* controls from FMU are valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 7) /* raw PWM from FMU is bypassing the mixer */
|
||||
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
|
||||
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
|
||||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
|
||||
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
|
||||
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 13) /* FMU was initialized and OK once */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 14) /* ST24 input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 15) /* SUMD input is valid */
|
||||
|
||||
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
|
||||
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
|
||||
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE (1 << 1) /* board temperature is high */
|
||||
#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* [1] servo current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* [1] accessory current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_FMU_LOST (1 << 4) /* timed out waiting for controls from FMU */
|
||||
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 5) /* timed out waiting for RC input */
|
||||
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 6) /* PWM configuration or output was bad */
|
||||
#define PX4IO_P_STATUS_ALARMS_VSERVO_FAULT (1 << 7) /* [2] VServo was out of the valid range (2.5 - 5.5 V) */
|
||||
|
||||
#define PX4IO_P_STATUS_VBATT 4 /* [1] battery voltage in mV */
|
||||
#define PX4IO_P_STATUS_IBATT 5 /* [1] battery current (raw ADC) */
|
||||
#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */
|
||||
#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */
|
||||
#define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */
|
||||
|
||||
#define PX4IO_P_STATUS_MIXER 9 /* mixer actuator limit flags */
|
||||
#define PX4IO_P_STATUS_MIXER_LOWER_LIMIT (1 << 0) /**< at least one actuator output has reached lower limit */
|
||||
#define PX4IO_P_STATUS_MIXER_UPPER_LIMIT (1 << 1) /**< at least one actuator output has reached upper limit */
|
||||
#define PX4IO_P_STATUS_MIXER_YAW_LIMIT (1 << 2) /**< yaw control is limited because it causes output clipping */
|
||||
|
||||
/* array of post-mix actuator outputs, -10000..10000 */
|
||||
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of PWM servo output values, microseconds */
|
||||
#define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of raw RC input values, microseconds */
|
||||
#define PX4IO_PAGE_RAW_RC_INPUT 4
|
||||
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */
|
||||
#define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_RC_OK (1 << 4) /* RC reception ok */
|
||||
|
||||
#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
|
||||
#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
|
||||
#define PX4IO_P_RAW_FRAME_COUNT 4 /* Number of total received frames (wrapping counter) */
|
||||
#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */
|
||||
#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */
|
||||
|
||||
/* array of scaled RC input values, -10000..10000 */
|
||||
#define PX4IO_PAGE_RC_INPUT 5
|
||||
#define PX4IO_P_RC_VALID 0 /* bitmask of valid controls */
|
||||
#define PX4IO_P_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT controls from here */
|
||||
|
||||
/* array of raw ADC values */
|
||||
#define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */
|
||||
|
||||
/* PWM servo information */
|
||||
#define PX4IO_PAGE_PWM_INFO 7
|
||||
#define PX4IO_RATE_MAP_BASE 0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */
|
||||
|
||||
/* setup page */
|
||||
#define PX4IO_PAGE_SETUP 50
|
||||
#define PX4IO_P_SETUP_FEATURES 0
|
||||
#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT (1 << 0) /**< enable S.Bus v1 output */
|
||||
#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) /**< enable S.Bus v2 output */
|
||||
#define PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) /**< enable PWM RSSI parsing */
|
||||
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) /**< enable ADC RSSI parsing */
|
||||
|
||||
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
|
||||
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
|
||||
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
|
||||
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
|
||||
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
|
||||
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
|
||||
#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
|
||||
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */
|
||||
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
|
||||
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */
|
||||
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
|
||||
#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE (1 << 10) /* If set then on FMU failure override is immediate. Othewise it waits for the mode switch to go past the override thrshold */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
|
||||
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4IO_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
#define PX4IO_P_SETUP_RELAYS 5 /* bitmask of relay/switch outputs, 0 = off, 1 = on */
|
||||
#define PX4IO_P_SETUP_RELAYS_POWER1 (1<<0) /* hardware rev [1] power relay 1 */
|
||||
#define PX4IO_P_SETUP_RELAYS_POWER2 (1<<1) /* hardware rev [1] power relay 2 */
|
||||
#define PX4IO_P_SETUP_RELAYS_ACC1 (1<<2) /* hardware rev [1] accessory power 1 */
|
||||
#define PX4IO_P_SETUP_RELAYS_ACC2 (1<<3) /* hardware rev [1] accessory power 2 */
|
||||
#else
|
||||
#define PX4IO_P_SETUP_RELAYS_PAD 5
|
||||
#endif
|
||||
|
||||
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* hardware rev [2] servo voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_DSM 7 /* DSM bind state */
|
||||
enum { /* DSM bind states */
|
||||
dsm_bind_power_down = 0,
|
||||
dsm_bind_power_up,
|
||||
dsm_bind_set_rx_out,
|
||||
dsm_bind_send_pulses,
|
||||
dsm_bind_reinit_uart
|
||||
};
|
||||
/* 8 */
|
||||
#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
|
||||
|
||||
#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */
|
||||
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
|
||||
|
||||
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
|
||||
/* storage space of 12 occupied by CRC */
|
||||
#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
|
||||
'armed' (PWM enabled) state - this is a non-data write and
|
||||
hence index 12 can safely be used. */
|
||||
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
|
||||
|
||||
#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */
|
||||
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_REVERSE 15 /**< Bitmask to reverse PWM channels 1-8 */
|
||||
#define PX4IO_P_SETUP_TRIM_ROLL 16 /**< Roll trim, in actuator units */
|
||||
#define PX4IO_P_SETUP_TRIM_PITCH 17 /**< Pitch trim, in actuator units */
|
||||
#define PX4IO_P_SETUP_TRIM_YAW 18 /**< Yaw trim, in actuator units */
|
||||
|
||||
/* autopilot control values, -10000..10000 */
|
||||
#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
|
||||
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID 64
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) /**< group 0 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) /**< group 1 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) /**< group 2 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) /**< group 3 is valid / received */
|
||||
|
||||
/* raw text load to the mixer parser - ignores offset */
|
||||
#define PX4IO_PAGE_MIXERLOAD 52
|
||||
|
||||
/* R/C channel config */
|
||||
#define PX4IO_PAGE_RC_CONFIG 53 /**< R/C input configuration */
|
||||
#define PX4IO_P_RC_CONFIG_MIN 0 /**< lowest input value */
|
||||
#define PX4IO_P_RC_CONFIG_CENTER 1 /**< center input value */
|
||||
#define PX4IO_P_RC_CONFIG_MAX 2 /**< highest input value */
|
||||
#define PX4IO_P_RC_CONFIG_DEADZONE 3 /**< band around center that is ignored */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /**< mapped input value */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 /**< magic value for mode switch */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS 5 /**< channel options bitmask */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
|
||||
#define PX4IO_P_RC_CONFIG_STRIDE 6 /**< spacing between channel config data */
|
||||
|
||||
/* PWM output - overrides mixer */
|
||||
#define PX4IO_PAGE_DIRECT_PWM 54 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM failsafe values - zero disables the output */
|
||||
#define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM failsafe values - zero disables the output */
|
||||
#define PX4IO_PAGE_SENSORS 56 /**< Sensors connected to PX4IO */
|
||||
#define PX4IO_P_SENSORS_ALTITUDE 0 /**< Altitude of an external sensor (HoTT or S.BUS2) */
|
||||
|
||||
/* Debug and test page - not used in normal operation */
|
||||
#define PX4IO_PAGE_TEST 127
|
||||
#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
|
||||
|
||||
/* PWM minimum values for certain ESCs */
|
||||
#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM maximum values for certain ESCs */
|
||||
#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM disarmed values that are active, even when SAFETY_SAFE */
|
||||
#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/**
|
||||
* As-needed mixer data upload.
|
||||
*
|
||||
* This message adds text to the mixer text buffer; the text
|
||||
* buffer is drained as the definitions are consumed.
|
||||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct px4io_mixdata {
|
||||
uint16_t f2i_mixer_magic;
|
||||
#define F2I_MIXER_MAGIC 0x6d74
|
||||
|
||||
uint8_t action;
|
||||
#define F2I_MIXER_ACTION_RESET 0
|
||||
#define F2I_MIXER_ACTION_APPEND 1
|
||||
|
||||
char text[0]; /* actual text size may vary */
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
/**
|
||||
* Serial protocol encapsulation.
|
||||
*/
|
||||
|
||||
#define PKT_MAX_REGS 32 // by agreement w/FMU
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct IOPacket {
|
||||
uint8_t count_code;
|
||||
uint8_t crc;
|
||||
uint8_t page;
|
||||
uint8_t offset;
|
||||
uint16_t regs[PKT_MAX_REGS];
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
#define PKT_CODE_READ 0x00 /* FMU->IO read transaction */
|
||||
#define PKT_CODE_WRITE 0x40 /* FMU->IO write transaction */
|
||||
#define PKT_CODE_SUCCESS 0x00 /* IO->FMU success reply */
|
||||
#define PKT_CODE_CORRUPT 0x40 /* IO->FMU bad packet reply */
|
||||
#define PKT_CODE_ERROR 0x80 /* IO->FMU register op error reply */
|
||||
|
||||
#define PKT_CODE_MASK 0xc0
|
||||
#define PKT_COUNT_MASK 0x3f
|
||||
|
||||
#define PKT_COUNT(_p) ((_p).count_code & PKT_COUNT_MASK)
|
||||
#define PKT_CODE(_p) ((_p).count_code & PKT_CODE_MASK)
|
||||
#define PKT_SIZE(_p) ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p))))
|
||||
|
||||
static const uint8_t crc8_tab[256] __attribute__((unused)) = {
|
||||
0x00, 0x07, 0x0E, 0x09, 0x1C, 0x1B, 0x12, 0x15,
|
||||
0x38, 0x3F, 0x36, 0x31, 0x24, 0x23, 0x2A, 0x2D,
|
||||
0x70, 0x77, 0x7E, 0x79, 0x6C, 0x6B, 0x62, 0x65,
|
||||
0x48, 0x4F, 0x46, 0x41, 0x54, 0x53, 0x5A, 0x5D,
|
||||
0xE0, 0xE7, 0xEE, 0xE9, 0xFC, 0xFB, 0xF2, 0xF5,
|
||||
0xD8, 0xDF, 0xD6, 0xD1, 0xC4, 0xC3, 0xCA, 0xCD,
|
||||
0x90, 0x97, 0x9E, 0x99, 0x8C, 0x8B, 0x82, 0x85,
|
||||
0xA8, 0xAF, 0xA6, 0xA1, 0xB4, 0xB3, 0xBA, 0xBD,
|
||||
0xC7, 0xC0, 0xC9, 0xCE, 0xDB, 0xDC, 0xD5, 0xD2,
|
||||
0xFF, 0xF8, 0xF1, 0xF6, 0xE3, 0xE4, 0xED, 0xEA,
|
||||
0xB7, 0xB0, 0xB9, 0xBE, 0xAB, 0xAC, 0xA5, 0xA2,
|
||||
0x8F, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9D, 0x9A,
|
||||
0x27, 0x20, 0x29, 0x2E, 0x3B, 0x3C, 0x35, 0x32,
|
||||
0x1F, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0D, 0x0A,
|
||||
0x57, 0x50, 0x59, 0x5E, 0x4B, 0x4C, 0x45, 0x42,
|
||||
0x6F, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7D, 0x7A,
|
||||
0x89, 0x8E, 0x87, 0x80, 0x95, 0x92, 0x9B, 0x9C,
|
||||
0xB1, 0xB6, 0xBF, 0xB8, 0xAD, 0xAA, 0xA3, 0xA4,
|
||||
0xF9, 0xFE, 0xF7, 0xF0, 0xE5, 0xE2, 0xEB, 0xEC,
|
||||
0xC1, 0xC6, 0xCF, 0xC8, 0xDD, 0xDA, 0xD3, 0xD4,
|
||||
0x69, 0x6E, 0x67, 0x60, 0x75, 0x72, 0x7B, 0x7C,
|
||||
0x51, 0x56, 0x5F, 0x58, 0x4D, 0x4A, 0x43, 0x44,
|
||||
0x19, 0x1E, 0x17, 0x10, 0x05, 0x02, 0x0B, 0x0C,
|
||||
0x21, 0x26, 0x2F, 0x28, 0x3D, 0x3A, 0x33, 0x34,
|
||||
0x4E, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5C, 0x5B,
|
||||
0x76, 0x71, 0x78, 0x7F, 0x6A, 0x6D, 0x64, 0x63,
|
||||
0x3E, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2C, 0x2B,
|
||||
0x06, 0x01, 0x08, 0x0F, 0x1A, 0x1D, 0x14, 0x13,
|
||||
0xAE, 0xA9, 0xA0, 0xA7, 0xB2, 0xB5, 0xBC, 0xBB,
|
||||
0x96, 0x91, 0x98, 0x9F, 0x8A, 0x8D, 0x84, 0x83,
|
||||
0xDE, 0xD9, 0xD0, 0xD7, 0xC2, 0xC5, 0xCC, 0xCB,
|
||||
0xE6, 0xE1, 0xE8, 0xEF, 0xFA, 0xFD, 0xF4, 0xF3
|
||||
};
|
||||
|
||||
static uint8_t crc_packet(struct IOPacket *pkt) __attribute__((unused));
|
||||
static uint8_t
|
||||
crc_packet(struct IOPacket *pkt)
|
||||
{
|
||||
uint8_t *end = (uint8_t *)(&pkt->regs[PKT_COUNT(*pkt)]);
|
||||
uint8_t *p = (uint8_t *)pkt;
|
||||
uint8_t c = 0;
|
||||
|
||||
while (p < end) {
|
||||
c = crc8_tab[c ^ * (p++)];
|
||||
}
|
||||
|
||||
return c;
|
||||
}
|
||||
@@ -0,0 +1,258 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/px4io_flash/px4io_flash.c"
|
||||
* @author Kevin van Hecke
|
||||
* Flashes the px4io f1 through the px4 bootloader.
|
||||
* Assumes the telem2 port on the Pixhawk is connected to a ttyACM device (blackmagic probe)
|
||||
*/
|
||||
|
||||
#include "modules/px4io_flash/px4io_flash.h"
|
||||
//#include "subsystems/datalink/downlink.h"
|
||||
#include "modules/px4io_flash/protocol.h"
|
||||
#include "mcu_periph/sys_time_arch.h"
|
||||
#include "subsystems/intermcu/intermcu_ap.h"
|
||||
|
||||
// Serial Port
|
||||
#include "mcu_periph/uart.h"
|
||||
|
||||
// define coms link for px4io f1
|
||||
#define PX4IO_PORT (&((PX4IO_UART).device))
|
||||
#define TELEM2_PORT (&((TELEM2_UART).device))
|
||||
|
||||
// weird that these below are not in protocol.h, which is from the firmware px4 repo
|
||||
// below is copied from qgroundcontrol:
|
||||
#define PROTO_INSYNC 0x12 ///< 'in sync' byte sent before status
|
||||
#define PROTO_EOC 0x20 ///< end of command
|
||||
// Reply bytes
|
||||
#define PROTO_OK 0x10 ///< INSYNC/OK - 'ok' response
|
||||
#define PROTO_FAILED 0x11 ///< INSYNC/FAILED - 'fail' response
|
||||
#define PROTO_INVALID 0x13 ///< INSYNC/INVALID - 'invalid' response for bad commands
|
||||
// Command bytes
|
||||
#define PROTO_GET_SYNC 0x21 ///< NOP for re-establishing sync
|
||||
#define PROTO_GET_DEVICE 0x22 ///< get device ID bytes
|
||||
#define PROTO_CHIP_ERASE 0x23 ///< erase program area and reset program address
|
||||
#define PROTO_LOAD_ADDRESS 0x24 ///< set next programming address
|
||||
#define PROTO_PROG_MULTI 0x27 ///< write bytes at program address and increment
|
||||
#define PROTO_GET_CRC 0x29 ///< compute & return a CRC
|
||||
#define PROTO_BOOT 0x30 ///< boot the application
|
||||
|
||||
bool_t setToBootloaderMode;
|
||||
|
||||
void px4ioflash_init(void)
|
||||
{
|
||||
setToBootloaderMode = FALSE;
|
||||
}
|
||||
|
||||
void px4ioflash_event(void)
|
||||
{
|
||||
// setToBootloaderMode=true;
|
||||
if (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
|
||||
if (!setToBootloaderMode) {
|
||||
//ignore anything coming from IO if not in bootloader mode (which should be nothing)
|
||||
} else {
|
||||
//relay everything from IO to the laptop
|
||||
unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
|
||||
TELEM2_PORT->put_byte(TELEM2_PORT->periph, b);
|
||||
}
|
||||
}
|
||||
|
||||
//TODO: check if timeout was surpassed
|
||||
if (TELEM2_PORT->char_available(TELEM2_PORT->periph) && !setToBootloaderMode) {
|
||||
//data was received on the pc uart, so
|
||||
//stop all intermcu comminication:
|
||||
disable_inter_comm(true);
|
||||
//send the reboot to bootloader command:
|
||||
|
||||
/*
|
||||
* The progdieshit define is very usefull, if for whatever reason the (normal, not bootloader) firmware on the IO chip became disfunct.
|
||||
* In that case:
|
||||
* 1. enable this define
|
||||
* 2. build and upload the fmu f4 chip (ap target in pprz center)
|
||||
* 3. build the io code, and convert the firmware using the following command:
|
||||
* /home/houjebek/paparazzi/sw/tools/pixhawk/px_mkfw.py --prototype "/home/houjebek/px4/Firmware/Images/px4io-v2.prototype" --image /home/houjebek/paparazzi/var/aircrafts/Iris/fbw/fbw.bin > /home/houjebek/paparazzi/var/aircrafts/Iris/fbw/fbw.px4
|
||||
* 4. Start the following command:
|
||||
* /home/houjebek/paparazzi/sw/tools/pixhawk/px_uploader.py --port "/dev/serial/by-id/usb-FTDI_TTL232R-3V3_FT906KBO-if00-port0" /home/houjebek/paparazzi/var/aircrafts/Iris/fbw/fbw.px4
|
||||
* 5a. Either, boot the Pixhawk (reconnect usb) holding the IO reset button until the FMU led stops blinking fast (i.e. exits its own bootloader)
|
||||
* 5b Or, press the IO reset button on the pixhawk
|
||||
* 6. Watch the output of the command of step 4, it should recognize the IO bootloader and start flashing. If not try repeating step 5a.
|
||||
* 7. Don forget to disable the define and upload the ap again :)
|
||||
*/
|
||||
//#define progdieshit
|
||||
|
||||
#ifndef progdieshit
|
||||
static struct IOPacket dma_packet;
|
||||
dma_packet.count_code = 0x40 + 0x01;
|
||||
dma_packet.crc = 0;
|
||||
dma_packet.page = PX4IO_PAGE_SETUP;
|
||||
dma_packet.offset = PX4IO_P_SETUP_REBOOT_BL;
|
||||
dma_packet.regs[0] = PX4IO_REBOOT_BL_MAGIC;
|
||||
dma_packet.crc = crc_packet(&dma_packet);
|
||||
struct IOPacket *pkt = &dma_packet;
|
||||
uint8_t *p = (uint8_t *)pkt;
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[0]);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[1]);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[2]);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[3]);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[4]);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, p[5]);
|
||||
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'E');
|
||||
// for (int i=0;i<6;i++) {
|
||||
// unsigned char tmp[3];
|
||||
// itoa(p[i],tmp,16);
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,tmp[0]);
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,tmp[1]);
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
// }
|
||||
|
||||
sys_time_usleep(5000); // this seems to be close to the minimum delay necessary to process this packet at the IO side
|
||||
//the pixhawk IO chip should respond with:
|
||||
// 0x00 ( PKT_CODE_SUCCESS )
|
||||
// 0xe5
|
||||
// 0x32
|
||||
// 0x0a
|
||||
//After that, the IO chips reboots into bootloader mode, in which it will stay for a short period
|
||||
//The baudrate in bootloader mode ic changed to 115200 (normal operating baud is 1500000, at least for original pixhawk fmu firmware)
|
||||
|
||||
//state machine
|
||||
int state = 0;
|
||||
while (state < 4 && PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
|
||||
|
||||
unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
|
||||
switch (state) {
|
||||
case (0) :
|
||||
if (b == PKT_CODE_SUCCESS) { state++; } else { state = 0; }
|
||||
break;
|
||||
case (1) :
|
||||
if (b == 0xe5) { state++; } else { state = 0; }
|
||||
break;
|
||||
case (2) :
|
||||
if (b == 0x32) { state++; } else { state = 0; }
|
||||
break;
|
||||
case (3) :
|
||||
if (b == 0x0a) { state++; } else { state = 0; }
|
||||
break;
|
||||
default :
|
||||
TELEM2_PORT->put_byte(TELEM2_PORT->periph, 'b');
|
||||
break;
|
||||
}
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,state+48);
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
}
|
||||
#else
|
||||
int state = 4;
|
||||
#endif
|
||||
if (state == 4) {
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'6');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
uart_periph_set_baudrate(PX4IO_PORT->periph, B115200);
|
||||
/* look for the bootloader for 150 ms */
|
||||
int ret = 0;
|
||||
for (int i = 0; i < 15 && !ret ; i++) {
|
||||
sys_time_usleep(10000);
|
||||
|
||||
|
||||
//send a get_sync command in order to keep the io in bootloader mode
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, PROTO_GET_SYNC);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, PROTO_EOC);
|
||||
|
||||
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'6');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'a');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
|
||||
//get_sync should be replied with, so check if that happens and
|
||||
//all other bytes are discarded, hopefully those were not important
|
||||
//(they may be caused by sending multiple syncs)
|
||||
while (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {
|
||||
unsigned char b = PX4IO_PORT->get_byte(PX4IO_PORT->periph);
|
||||
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'6');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'b');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
|
||||
if (b == PROTO_INSYNC) {
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'7');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
|
||||
setToBootloaderMode = true;
|
||||
ret = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (setToBootloaderMode) {
|
||||
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'8');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
|
||||
//if successfully entered bootloader mode, clear any remaining bytes (which may have a function, but I did not check)
|
||||
while (PX4IO_PORT->char_available(PX4IO_PORT->periph)) {PX4IO_PORT->get_byte(PX4IO_PORT->periph);}
|
||||
}
|
||||
|
||||
#ifndef progdieshit
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'S');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'9');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
#endif
|
||||
|
||||
} else {
|
||||
TELEM2_PORT->put_byte(TELEM2_PORT->periph, 'E');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'r');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'r');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'o');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'r');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\n');
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,'\r');
|
||||
}
|
||||
} else if (TELEM2_PORT->char_available(TELEM2_PORT->periph)) {
|
||||
//already in bootloader mode, just directly relay data
|
||||
unsigned char b = TELEM2_PORT->get_byte(TELEM2_PORT->periph);
|
||||
PX4IO_PORT->put_byte(PX4IO_PORT->periph, b);
|
||||
// TELEM2_PORT->put_byte(TELEM2_PORT->periph,b);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -0,0 +1,33 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/px4io_flash/px4io_flash.h"
|
||||
* @author Kevin van Hecke
|
||||
* Flashes the px4io f1 through the px4 bootloader.
|
||||
*/
|
||||
|
||||
#ifndef PX4IO_FLASH_H
|
||||
#define PX4IO_FLASH_H
|
||||
|
||||
extern void px4ioflash_init(void);
|
||||
extern void px4ioflash_event(void);
|
||||
|
||||
#endif
|
||||
|
||||
@@ -0,0 +1,30 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind.c"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.h"
|
||||
|
||||
void spektrum_soft_bind_init() {}
|
||||
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind.h"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#ifndef SPEKTRUM_SOFT_BIND_H
|
||||
#define SPEKTRUM_SOFT_BIND_H
|
||||
|
||||
#if defined FBW
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.h"
|
||||
#else
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_ap.h"
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
@@ -0,0 +1,38 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind_ap.c"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_ap.h"
|
||||
#include "subsystems/intermcu/intermcu_ap.h"
|
||||
#include "led.h"
|
||||
|
||||
void spektrum_soft_bind_init(void) {}
|
||||
|
||||
uint8_t bind_soft_value;
|
||||
void spektrum_soft_bind_click(uint8_t val __attribute__((unused)))
|
||||
{
|
||||
intermcu_send_spektrum_bind();
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,37 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind_ap.h"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#ifndef SPEKTRUM_AP_SOFT_BIND_H
|
||||
#define SPEKTRUM_AP_SOFT_BIND_H
|
||||
|
||||
#include "std.h"
|
||||
|
||||
extern void spektrum_soft_bind_init(void);
|
||||
extern void spektrum_soft_bind_click(uint8_t val);
|
||||
|
||||
extern uint8_t bind_soft_value;
|
||||
|
||||
#endif
|
||||
|
||||
@@ -0,0 +1,54 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.c"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.h"
|
||||
#include "subsystems/intermcu/intermcu_fbw.h"
|
||||
#include "mcu.h"
|
||||
#include "subsystems/radio_control.h"
|
||||
#include "mcu_periph/sys_time_arch.h"
|
||||
|
||||
#include "led.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
|
||||
void spektrum_soft_bind_init(void)
|
||||
{
|
||||
gpio_setup_output(SPEKTRUM_POWER_PIN_PORT, SPEKTRUM_POWER_PIN);
|
||||
gpio_set(SPEKTRUM_POWER_PIN_PORT, SPEKTRUM_POWER_PIN);
|
||||
}
|
||||
|
||||
void received_spektrum_soft_bind(void)
|
||||
{
|
||||
|
||||
//power cycle the spektrum
|
||||
gpio_clear(SPEKTRUM_POWER_PIN_PORT, SPEKTRUM_POWER_PIN);
|
||||
sys_time_usleep(100000);
|
||||
gpio_set(SPEKTRUM_POWER_PIN_PORT, SPEKTRUM_POWER_PIN);
|
||||
|
||||
//put to bind mode
|
||||
RADIO_CONTROL_BIND_IMPL_FUNC(); //basically = radio_control_spektrum_try_bind()
|
||||
|
||||
SpektrumUartInit();
|
||||
|
||||
}
|
||||
@@ -0,0 +1,34 @@
|
||||
/*
|
||||
* Copyright (C) Kevin van Hecke
|
||||
*
|
||||
* 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, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* @file "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.h"
|
||||
* @author Kevin van Hecke
|
||||
* Puts Spektrum in binding mode through software
|
||||
*/
|
||||
|
||||
#ifndef SPEKTRUM_FBW_SOFT_BIND_H
|
||||
#define SPEKTRUM_FBW_SOFT_BIND_H
|
||||
#include "std.h"
|
||||
|
||||
extern void spektrum_soft_bind_init(void);
|
||||
extern void received_spektrum_soft_bind(void);
|
||||
|
||||
#endif
|
||||
|
||||
@@ -55,7 +55,7 @@ struct w5100_periph {
|
||||
volatile uint16_t tx_extract_idx[W5100_BUFFER_NUM];
|
||||
volatile uint8_t work_tx[4];
|
||||
volatile uint8_t work_rx[4];
|
||||
uint8_t tx_running;
|
||||
volatile uint8_t tx_running;
|
||||
/** Generic device interface */
|
||||
struct link_device device;
|
||||
};
|
||||
@@ -90,7 +90,8 @@ static inline void w5100_read_buffer(struct pprz_transport *t)
|
||||
|
||||
#define W5100CheckAndParse(_dev, _trans) w5100_check_and_parse(&(_dev).device, &(_trans))
|
||||
|
||||
static inline void w5100_check_and_parse(struct link_device *dev, struct pprz_transport *trans) {
|
||||
static inline void w5100_check_and_parse(struct link_device *dev, struct pprz_transport *trans)
|
||||
{
|
||||
if (dev->char_available(dev->periph)) {
|
||||
w5100_read_buffer(trans);
|
||||
if (trans->trans_rx.msg_received) {
|
||||
|
||||
@@ -33,7 +33,9 @@
|
||||
#define INTERMCU_AP 0
|
||||
#define INTERMCU_FBW 1
|
||||
|
||||
#ifndef INTERMCU_LOST_CNT
|
||||
#define INTERMCU_LOST_CNT 25 /* 50ms with a 512Hz timer TODO fixed value */
|
||||
#endif
|
||||
|
||||
enum intermcu_status {
|
||||
INTERMCU_OK,
|
||||
|
||||
@@ -30,6 +30,10 @@
|
||||
#include "pprzlink/pprz_transport.h"
|
||||
#include "mcu_periph/uart.h"
|
||||
|
||||
#include "subsystems/datalink/telemetry.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "autopilot.h"
|
||||
|
||||
#if COMMANDS_NB > 8
|
||||
#error "INTERMCU UART CAN ONLY SEND 8 COMMANDS OR THE UART WILL BE OVERFILLED"
|
||||
#endif
|
||||
@@ -41,9 +45,21 @@ static struct pprz_transport intermcu_transport;
|
||||
struct intermcu_t inter_mcu;
|
||||
static inline void intermcu_parse_msg(struct transport_rx *trans, void (*rc_frame_handler)(void));
|
||||
|
||||
|
||||
|
||||
static void send_status(struct transport_tx *trans, struct link_device *dev)
|
||||
{
|
||||
pprz_msg_send_FBW_STATUS(trans, dev, AC_ID,
|
||||
&(radio_control.status), &(radio_control.frame_rate), &(inter_mcu.status), &electrical.vsupply,
|
||||
&electrical.current); // due to limitation of GCS, send the electrical from ap as if it comes from fbw...
|
||||
}
|
||||
|
||||
void intermcu_init(void)
|
||||
{
|
||||
pprz_transport_init(&intermcu_transport);
|
||||
|
||||
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_FBW_STATUS, send_status);
|
||||
|
||||
}
|
||||
|
||||
void intermcu_periodic(void)
|
||||
@@ -56,12 +72,28 @@ void intermcu_periodic(void)
|
||||
}
|
||||
}
|
||||
|
||||
static bool_t disable_comm;
|
||||
void disable_inter_comm(bool_t value)
|
||||
{
|
||||
disable_comm = value;
|
||||
}
|
||||
|
||||
void intermcu_set_actuators(pprz_t *command_values, uint8_t ap_mode __attribute__((unused)))
|
||||
{
|
||||
pprz_msg_send_IMCU_COMMANDS(&(intermcu_transport.trans_tx), intermcu_device,
|
||||
INTERMCU_AP, 0, COMMANDS_NB, command_values); //TODO: Fix status
|
||||
if (!disable_comm) {
|
||||
pprz_msg_send_IMCU_COMMANDS(&(intermcu_transport.trans_tx), intermcu_device,
|
||||
INTERMCU_AP, &autopilot_motors_on, COMMANDS_NB, command_values); //TODO: Append more status
|
||||
}
|
||||
}
|
||||
|
||||
void intermcu_send_spektrum_bind(void)
|
||||
{
|
||||
if (!disable_comm) {
|
||||
pprz_msg_send_IMCU_SPEKTRUM_SOFT_BIND(&(intermcu_transport.trans_tx), intermcu_device, INTERMCU_AP);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static inline void intermcu_parse_msg(struct transport_rx *trans, void (*rc_frame_handler)(void))
|
||||
{
|
||||
/* Parse the Inter MCU message */
|
||||
@@ -70,6 +102,7 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*rc_fram
|
||||
case DL_IMCU_RADIO_COMMANDS: {
|
||||
uint8_t i;
|
||||
uint8_t size = DL_IMCU_RADIO_COMMANDS_values_length(trans->payload);
|
||||
inter_mcu.status = DL_IMCU_RADIO_COMMANDS_status(trans->payload);
|
||||
int16_t *rc_values = DL_IMCU_RADIO_COMMANDS_values(trans->payload);
|
||||
for (i = 0; i < size; i++) {
|
||||
radio_control.values[i] = rc_values[i];
|
||||
@@ -92,14 +125,16 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*rc_fram
|
||||
|
||||
void RadioControlEvent(void (*frame_handler)(void))
|
||||
{
|
||||
/* Parse incoming bytes */
|
||||
if (intermcu_device->char_available(intermcu_device->periph)) {
|
||||
while (intermcu_device->char_available(intermcu_device->periph) && !intermcu_transport.trans_rx.msg_received) {
|
||||
parse_pprz(&intermcu_transport, intermcu_device->get_byte(intermcu_device->periph));
|
||||
}
|
||||
if (!disable_comm) {
|
||||
/* Parse incoming bytes */
|
||||
if (intermcu_device->char_available(intermcu_device->periph)) {
|
||||
while (intermcu_device->char_available(intermcu_device->periph) && !intermcu_transport.trans_rx.msg_received) {
|
||||
parse_pprz(&intermcu_transport, intermcu_device->get_byte(intermcu_device->periph));
|
||||
}
|
||||
|
||||
if (intermcu_transport.trans_rx.msg_received) {
|
||||
intermcu_parse_msg(&(intermcu_transport.trans_rx), frame_handler);
|
||||
if (intermcu_transport.trans_rx.msg_received) {
|
||||
intermcu_parse_msg(&(intermcu_transport.trans_rx), frame_handler);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -32,24 +32,20 @@
|
||||
|
||||
void intermcu_set_actuators(pprz_t *command_values, uint8_t ap_mode);
|
||||
void RadioControlEvent(void (*frame_handler)(void));
|
||||
void intermcu_send_spektrum_bind(void);
|
||||
void disable_inter_comm(bool_t value);
|
||||
|
||||
/* We need radio defines for the Autopilot */
|
||||
#define RADIO_THROTTLE 0
|
||||
#define RADIO_ROLL 1
|
||||
#define RADIO_PITCH 2
|
||||
#define RADIO_YAW 3
|
||||
#define RADIO_GEAR 4
|
||||
#define RADIO_FLAP 5
|
||||
#define RADIO_MODE 4
|
||||
#define RADIO_KILL_SWITCH 5
|
||||
#define RADIO_AUX1 5
|
||||
#define RADIO_AUX2 6
|
||||
#define RADIO_AUX3 7
|
||||
#define RADIO_CONTROL_NB_CHANNEL 8
|
||||
|
||||
#ifndef RADIO_MODE
|
||||
#define RADIO_MODE RADIO_GEAR
|
||||
#endif
|
||||
//#ifndef RADIO_KILL_SWITCH
|
||||
//#define RADIO_KILL_SWITCH RADIO_FLAP
|
||||
//#endif
|
||||
|
||||
#endif /* INTERMCU_AP_ROTORCRAFT_H */
|
||||
|
||||
@@ -29,6 +29,18 @@
|
||||
#include "subsystems/radio_control.h"
|
||||
#include "mcu_periph/uart.h"
|
||||
#include "pprzlink/pprz_transport.h"
|
||||
#include "modules/spektrum_soft_bind/spektrum_soft_bind_fbw.h"
|
||||
|
||||
#ifdef BOARD_PX4IO
|
||||
#include "libopencm3/cm3/scb.h"
|
||||
#include "led.h"
|
||||
#include "mcu_periph/sys_time.h"
|
||||
static uint8_t px4RebootSequence[] = {0x41, 0xd7, 0x32, 0x0a, 0x46, 0x39};
|
||||
static uint8_t px4RebootSequenceCount = 0;
|
||||
static bool_t px4RebootTimeout = FALSE;
|
||||
uint8_t autopilot_motors_on = FALSE;
|
||||
tid_t px4bl_tid; ///< id for time out of the px4 bootloader reset
|
||||
#endif
|
||||
|
||||
#if RADIO_CONTROL_NB_CHANNEL > 8
|
||||
#undef RADIO_CONTROL_NB_CHANNEL
|
||||
@@ -43,10 +55,15 @@ static struct pprz_transport intermcu_transport;
|
||||
struct intermcu_t inter_mcu;
|
||||
pprz_t intermcu_commands[COMMANDS_NB];
|
||||
static inline void intermcu_parse_msg(struct transport_rx *trans, void (*commands_frame_handler)(void));
|
||||
static inline void checkPx4RebootCommand(unsigned char b);
|
||||
|
||||
void intermcu_init(void)
|
||||
{
|
||||
pprz_transport_init(&intermcu_transport);
|
||||
#ifdef BOARD_PX4IO
|
||||
px4bl_tid = sys_time_register_timer(20.0, NULL);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void intermcu_periodic(void)
|
||||
@@ -59,10 +76,38 @@ void intermcu_periodic(void)
|
||||
}
|
||||
}
|
||||
|
||||
void intermcu_on_rc_frame(void)
|
||||
void intermcu_on_rc_frame(uint8_t fbw_mode)
|
||||
{
|
||||
|
||||
pprz_t values[8];
|
||||
|
||||
values[INTERMCU_RADIO_THROTTLE] = radio_control.values[RADIO_THROTTLE];
|
||||
values[INTERMCU_RADIO_ROLL] = radio_control.values[RADIO_ROLL];
|
||||
values[INTERMCU_RADIO_PITCH] = radio_control.values[RADIO_PITCH];
|
||||
values[INTERMCU_RADIO_YAW] = radio_control.values[RADIO_YAW];
|
||||
#ifdef RADIO_MODE
|
||||
values[INTERMCU_RADIO_MODE] = radio_control.values[RADIO_MODE];
|
||||
#endif
|
||||
#ifdef RADIO_KILL_SWITCH
|
||||
values[INTERMCU_RADIO_KILL_SWITCH] = radio_control.values[RADIO_KILL];
|
||||
#endif
|
||||
|
||||
#if defined (RADIO_AUX1) && defined (RADIO_KILL_SWITCH)
|
||||
#warning "RC AUX1 and KILL_SWITCH are on the same channel."
|
||||
#endif
|
||||
|
||||
#ifdef RADIO_AUX1
|
||||
values[INTERMCU_RADIO_AUX1] = radio_control.values[RADIO_AUX1];
|
||||
#endif
|
||||
#ifdef RADIO_AUX2
|
||||
values[INTERMCU_RADIO_AUX2] = radio_control.values[RADIO_AUX2];
|
||||
#endif
|
||||
#ifdef RADIO_AUX3
|
||||
values[INTERMCU_RADIO_AUX2] = radio_control.values[RADIO_AUX2];
|
||||
#endif
|
||||
|
||||
pprz_msg_send_IMCU_RADIO_COMMANDS(&(intermcu_transport.trans_tx), intermcu_device,
|
||||
INTERMCU_FBW, 0, RADIO_CONTROL_NB_CHANNEL, radio_control.values); //TODO: Fix status
|
||||
INTERMCU_FBW, &fbw_mode, RADIO_CONTROL_NB_CHANNEL, values);
|
||||
}
|
||||
|
||||
void intermcu_send_status(uint8_t mode)
|
||||
@@ -81,6 +126,8 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*command
|
||||
uint8_t i;
|
||||
uint8_t size = DL_IMCU_COMMANDS_values_length(trans->payload);
|
||||
int16_t *new_commands = DL_IMCU_COMMANDS_values(trans->payload);
|
||||
uint8_t status = DL_IMCU_COMMANDS_status(trans->payload);
|
||||
autopilot_motors_on = status & 0x1;
|
||||
for (i = 0; i < size; i++) {
|
||||
intermcu_commands[i] = new_commands[i];
|
||||
}
|
||||
@@ -91,6 +138,11 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*command
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(SPEKTRUM_HAS_SOFT_BIND_PIN) //TODO: make subscribable module parser
|
||||
case DL_IMCU_SPEKTRUM_SOFT_BIND:
|
||||
received_spektrum_soft_bind();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -101,10 +153,15 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*command
|
||||
|
||||
void InterMcuEvent(void (*frame_handler)(void))
|
||||
{
|
||||
|
||||
/* Parse incoming bytes */
|
||||
if (intermcu_device->char_available(intermcu_device->periph)) {
|
||||
while (intermcu_device->char_available(intermcu_device->periph) && !intermcu_transport.trans_rx.msg_received) {
|
||||
parse_pprz(&intermcu_transport, intermcu_device->get_byte(intermcu_device->periph));
|
||||
unsigned char b = intermcu_device->get_byte(intermcu_device->periph);
|
||||
#ifdef BOARD_PX4IO
|
||||
checkPx4RebootCommand(b);
|
||||
#endif
|
||||
parse_pprz(&intermcu_transport, b);
|
||||
}
|
||||
|
||||
if (intermcu_transport.trans_rx.msg_received) {
|
||||
@@ -112,3 +169,44 @@ void InterMcuEvent(void (*frame_handler)(void))
|
||||
}
|
||||
}
|
||||
}
|
||||
#ifdef BOARD_PX4IO
|
||||
static inline void checkPx4RebootCommand(unsigned char b)
|
||||
{
|
||||
if (!px4RebootTimeout) {
|
||||
|
||||
|
||||
if (sys_time_check_and_ack_timer(px4bl_tid)) {
|
||||
//time out the possibility to reboot to the px4 bootloader, to prevent unwanted restarts during flight
|
||||
px4RebootTimeout = true;
|
||||
sys_time_cancel_timer(px4bl_tid);
|
||||
return;
|
||||
}
|
||||
|
||||
LED_ON(SYS_TIME_LED);
|
||||
|
||||
if (b == px4RebootSequence[px4RebootSequenceCount]) {
|
||||
px4RebootSequenceCount++;
|
||||
} else {
|
||||
px4RebootSequenceCount = 0;
|
||||
}
|
||||
|
||||
if (px4RebootSequenceCount >= 6) { // 6 = length of rebootSequence + 1
|
||||
px4RebootSequenceCount = 0; // should not be necessary...
|
||||
|
||||
//send some magic back
|
||||
//this is the same as the Pixhawk IO code would send
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x00);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0xe5);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x32);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x0a);
|
||||
intermcu_device->put_byte(intermcu_device->periph,
|
||||
0x66); // dummy byte, seems to be necessary otherwise one byte is missing at the fmu side...
|
||||
|
||||
while (((struct uart_periph *)(intermcu_device->periph))->tx_running) {LED_TOGGLE(SYS_TIME_LED);} // tx_running is volatile now, so LED_TOGGLE not necessary anymore
|
||||
|
||||
LED_OFF(SYS_TIME_LED);
|
||||
scb_reset_system();
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -29,9 +29,23 @@
|
||||
|
||||
#include "subsystems/intermcu.h"
|
||||
|
||||
extern uint8_t autopilot_motors_on;
|
||||
extern pprz_t intermcu_commands[COMMANDS_NB];
|
||||
void intermcu_on_rc_frame(void);
|
||||
void intermcu_on_rc_frame(uint8_t fbw_mode);
|
||||
void intermcu_send_status(uint8_t mode);
|
||||
void InterMcuEvent(void (*frame_handler)(void));
|
||||
|
||||
|
||||
/* We need radio defines for the Autopilot */
|
||||
#define INTERMCU_RADIO_THROTTLE 0
|
||||
#define INTERMCU_RADIO_ROLL 1
|
||||
#define INTERMCU_RADIO_PITCH 2
|
||||
#define INTERMCU_RADIO_YAW 3
|
||||
#define INTERMCU_RADIO_MODE 4
|
||||
#define INTERMCU_RADIO_KILL_SWITCH 5
|
||||
#define INTERMCU_RADIO_AUX1 5
|
||||
#define INTERMCU_RADIO_AUX2 6
|
||||
#define INTERMCU_RADIO_AUX3 7
|
||||
#define INTERMCU_RADIO_CONTROL_NB_CHANNEL 8
|
||||
|
||||
#endif /* INTERMCU_FBW_ROTORCRAFT_H */
|
||||
|
||||
@@ -64,7 +64,7 @@ void radio_control_periodic_task(void)
|
||||
radio_control.time_since_last_frame++;
|
||||
}
|
||||
|
||||
#if defined RADIO_CONTROL_LED
|
||||
#if defined(RADIO_CONTROL_LED)
|
||||
if (radio_control.status == RC_OK) {
|
||||
LED_ON(RADIO_CONTROL_LED);
|
||||
} else {
|
||||
|
||||
@@ -19,6 +19,11 @@
|
||||
* Boston, MA 02111-1307, USA.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file test_datalink.c
|
||||
*
|
||||
* Periodically sends ALIVE (10Hz) and ping/pong (every 5s) telemetry messages.
|
||||
*/
|
||||
#define DATALINK_C
|
||||
|
||||
#include BOARD_CONFIG
|
||||
@@ -50,6 +55,7 @@ static inline void main_init(void)
|
||||
{
|
||||
mcu_init();
|
||||
sys_time_register_timer((1. / PERIODIC_FREQUENCY), NULL);
|
||||
downlink_init();
|
||||
}
|
||||
|
||||
static inline void main_periodic(void)
|
||||
@@ -74,3 +80,4 @@ void dl_parse_msg(void)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Executable
+6
@@ -0,0 +1,6 @@
|
||||
#!/usr/bin/python
|
||||
# temporary solution to print a message to reconnect the usb cable
|
||||
#At some point hopefully this can be automated (without replugging)
|
||||
print("\n ")
|
||||
print("**** Please reconnect the usb cable now! *****")
|
||||
print(" \n")
|
||||
@@ -0,0 +1,12 @@
|
||||
{
|
||||
"board_id": 9,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the PX4FMUv2 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "PX4FMUv2",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user