Eachine Trashcan support (#2540)

Co-authored-by: Open UAS <>
Co-authored-by: Tom van Dijk <tomvand@users.noreply.github.com>
This commit is contained in:
Tom van Dijk
2020-07-03 15:52:32 +02:00
committed by GitHub
parent 94b1c3d24f
commit 1cc01d4653
46 changed files with 7098 additions and 1 deletions
+1
View File
@@ -65,6 +65,7 @@ paparazzi.sublime-workspace
/conf/maps.xml
/conf/gps/ublox_conf
!/conf/simulator/gazebo/**/*.config
/conf/tools/blacklisted
# /doc/pprz_algebra/
/doc/pprz_algebra/headfile.log
+2
View File
@@ -51,6 +51,7 @@ ifdef DFU_PRODUCT
DFU_PRODUCT_CMD = --product=$(DFU_PRODUCT)
endif
upload: $(OBJDIR)/$(TARGET).bin
$(DFU_PRE_UPLOAD_CMD)
@echo "Using stm32 mem dfu loader"
$(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $(DFU_PRODUCT_CMD) $(DFU_ADDR_CMD) $^
@@ -72,6 +73,7 @@ DFUSE_VERIFY_ADDRESS = $(DFU_ADDR):$(DFU_SIZE)
endif
upload: $(OBJDIR)/$(TARGET).bin
$(DFU_UTIL_PRE_UPLOAD_CMD)
@echo "Using dfu-util at $(DFU_ADDR)"
$(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^
ifeq ($(VERIFY),1)
+490
View File
@@ -0,0 +1,490 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Trashcan">
<description>
* Airframe for the regular "Trashcan" Quadrotor frame equipped with to validate all onboard functionally.
+ Autopilot: Default Crazybee F4 Pro STM32F4 and all that comes with it
+ Actuators: Default onboard Blheli S ESCs see http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
+ Telemetry: Default WiFi Via ESP8266 see
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out on LED pin
NOTES:
+ All set to expect flying on 2s LiPo battery, 1s LiPo battery possible but no gains set (yet..)
+ Removed Camera and Video TX to be replaced by a JeVois (www.jevois.org) camera on Uart1
+ RC control also possible via wifi telemetry module
+ Vison: added a JeVois on UART1 TX/RX
+ RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out,
+ Wifi telemetry module also allows RC
WIP:
+ GPS: uBlox SAM M8Q with Magneto n Baro GNSS
</description>
<firmware name="rotorcraft">
<target name="ap" board="crazybee_f4_1.0">
<configure name="NO_LUFTBOOT" value="1"/>
<configure name="USE_BARO_BOARD" value="FALSE"/>
<define name="AUTOPILOT_DISABLE_AHRS_KILL"/> <!-- Starts in KILL, but can now switch to NAV -->
<define name="AHRS_ALIGNER_SAMPLES_NB" value="1200"/> <!--When fidly plugging in a battery, aircraft kind of wobbly, now avoid messing up the aligner this way -->
<!-- <define name="LOW_NOISE_THRESHOLD" value="30000"/>-->
<!-- <define name="LOW_NOISE_TIME" value="10"/>-->
<!-- 2 kHz periodic -->
<configure name="PERIODIC_FREQUENCY" value="2048"/>
<define name="HFF_PRESCALER" value="40"/><!-- FIXME: determine fully correct one-->
<define name="AHRS_PROPAGATE_FREQUENCY" value="2000"/>
<configure name="AHRS_CORRECT_FREQUENCY" value="2000"/>
<configure name="AHRS_MAG_CORRECT_FREQUENCY" value="50"/> <!-- 75 or 160 max -->
<!-- set Gyro/Accel output rate to 2kHz at 8kHz internal sampling -->
<define name="IMU_MPU_LOWPASS_FILTER" value="MPU60X0_DLPF_256HZ"/><!--This sets the internal sample rate to 8KHz. -->
<define name="IMU_MPU_ACCEL_LOWPASS_FILTER" value="MPU60X0_DLPF_ACC_44HZ"/><!-- FIXME check value -->
<define name="IMU_MPU_SMPLRT_DIV" value="3"/> <!-- for 1khz periodic IMU_MPU_SMPLRT_DIV=7 sr = gr(8) /1+IMU_MPU_SMPLRT_DIV (1+7/8=1khz-->
<configure name="NAVIGATION_FREQUENCY" value="16"/>
<configure name="CONTROL_FREQUENCY" value="2000"/>
<configure name="TELEMETRY_FREQUENCY" value="120"/>
<configure name="MODULES_FREQUENCY" value="2048"/>
<define name="USE_PERSISTENT_SETTINGS" value="TRUE"/><!-- handy with the short flight time between tuning sets, not tested if it works yet, this board we have 16kb reserved -->
<define name="BAT_CHECKER_DELAY" value="70"/> <!-- to avoid bat low spike detection when strong up movement withch draws short sudden power-->
<define name="CATASTROPHIC_BATTERY_KILL_DELAY" value="90"/> <!-- in 10/s seconds-->
</target>
<module name="radio_control" type="cc2500_frsky">
<define name="CC2500_RX_LED" value="LED_2"/>
<define name="CC2500_BIND_BUTTON" value="BIND_BUTTON"/>
<define name="CC2500_TELEMETRY_SENSORS" value="SENSOR_NONE"/>
</module>
<module name="motor_mixing"/>
<module name="actuators" type="pwm">
<define name="SERVO_HZ" value="480"/>
</module>
<module name="dfu_command"/>
<!-- <module name="telemetry" type="transparent_usb"/> -->
<module name="telemetry" type="transparent_frsky_x"/>
<module name="imu" type="mpu6000">
<configure name="IMU_MPU_SPI_DEV" value="spi1"/>
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
<!-- define name="ICM20608"/> --> <!-- Not used atm -->
<!-- To be able (for now) to set AP IMU orientaion -->
<define name="IMU_GYRO_P_SIGN" value="1"/>
<define name="IMU_GYRO_Q_SIGN" value="-1"/>
<define name="IMU_GYRO_R_SIGN" value="-1"/>
<define name="IMU_ACCEL_X_SIGN" value="1"/>
<define name="IMU_ACCEL_Y_SIGN" value="-1"/>
<define name="IMU_ACCEL_Z_SIGN" value="-1"/>
</module>
<!-- not all are tested or tuned -->
<!-- <module name="stabilization" type="rate"/>--><!-- not working yet..)
<!-- <module name="stabilization" type="rate_indi"/> -->
<module name="stabilization" type="int_quat"/>
<!--<module name="stabilization" type="float_quat"/>-->
<!-- <module name="stabilization" type="indi_simple" /> -->
<!-- <module name="stabilization" type="indi" /> -->
<module name="ins" type="extended"/>
<!-- Not yet tested -->
<!--<module name="osd_max7456">
<configure name="MAX7456_SPI_DEV" value="SPI2"/>
<configure name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1"/>
</module>-->
<!-- <module name="filter_1euro_imu"> -->
<!--<define name="IMU_F1E_ID" value="30"/>-->
<!--<define name="AHRS_ICQ_IMU_ID" value="F1E_IMU_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="F1E_IMU_ID"/>-->
<!-- </module> -->
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="ahrs" type="float_cmpl_quat">
<!--<define name="AHRS_ICQ_IMU_ID" value="IMU_F1E_ID"/>
<define name="AHRS_ALIGNER_IMU_ID" value="IMU_F1E_ID"/>-->
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/> <!-- True for Optitrack false for real magneto-->
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/> <!-- for dronerace -->
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="0"/> <!-- TODO: determine best... Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. -->
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="FALSE"/> <!-- apply a low pass filter on rotational velocity"-->
</module>
<!-- WIP for setting values e.g. P/D roll tune via RC Tranmitter, need a new setting file WIP -->
<!--<module name="settings" type="rc"/>-->
<!-- only for... dronerace... -->
<!--
<module name="dronerace"/>
-->
<!-- Not yet used ATM
<module name="jevois_mavlink">
<configure name="JEVOIS_UART" value="UART1"/>
<configure name="JEVOIS_BAUD" value="B115200"/>
</module>
-->
<module name="gps" type="datalink"/> <!-- using optitrack and natnet2ivy -->
<!-- No I2C bus yet... still need to find some good spot for I2C pins... except straigt on MCU solder blobs -->
<!--
<module name="gps" type="ublox">
<configure name="GPS_PORT" value="I2C"/>
</module>
-->
<!--<module name="geo_mag"/>
<<module name="air_data"/>-->
<!-- below temporary until tested then disable it -->
<!-- <module name="send_imu_mag_current"/> -->
<!--
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="radio_control" type="ppm">
<define name="RADIO_CONTROL_NB_CHANNEL" value="8"/>
</module>
</target>
-->
<!-- <target name="FPV Racing" board="crazybee_f4_1.0">
WIP
For FPV setup only
No GPS
No Baro
No Magneto
Highest loop rate possible for board
Flip module
Module for OSD
Tuned for Race and ACRO
Try INDI full
</target>
-->
</firmware>
<servos driver="Pwm">
<servo name="FL" no="3" min="1000" neutral="1030" max="2000"/> <!-- maybe shorter on the cost of resolution... but low high differcnce MUST be bigger than 140-->
<servo name="FR" no="1" min="1000" neutral="1030" max="2000"/>
<servo name="BR" no="0" min="1000" neutral="1030" max="2000"/>
<servo name="BL" no="2" min="1000" neutral="1030" max="2000"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="REVERSE" value="TRUE"/>
<define name="TYPE" value="QUAD_X"/>
</section>
<!-- in case we need much more precise mixing use the table here instead of motor_mixing_run
<!-- section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section-->
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="FL" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="FR" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BR" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BL" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="FILTER_1EURO" prefix="FILTER_1EURO_">
<define name="ENABLED" value="FALSE"/> <!-- activate or not the filter by default -->
<define name="GYRO_MINCUTOFF" value="10."/> <!-- minimum cutoff freq for gyro signal -->
<define name="GYRO_BETA" value="0.1"/> <!-- adaptation coefficient for gyro signal -->
<define name="ACCEL_MINCUTOFF" value="0.1"/> <!-- minimum cutoff freq for accel signal -->
<define name="ACCEL_BETA" value="0.01"/> <!-- adaptation coefficient for accel signal -->
<!--<define name="FREQ" value="512"set fixed frequency, if not defined but INS/AHRS_PROPAGATE_FREQUENCY is defined it is used, otherwise autofreq is used-->
</section>
<section name="IMU" prefix="IMU_">
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
<!-- Tere is no MAG per default, but in case one adds one , make it correct -->
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<!-- replace this with your own calibration -->
<define name="ACCEL_X_NEUTRAL" value="0"/>
<define name="ACCEL_Y_NEUTRAL" value="0"/>
<define name="ACCEL_Z_NEUTRAL" value="0"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="8.0" integer="16"/>
<define name="MAG_Y_SENS" value="8.0" integer="16"/>
<define name="MAG_Z_SENS" value="8.0" integer="16"/>
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="2400." unit="deg/s"/>
<define name="SP_MAX_Q" value="2400." unit="deg/s"/>
<define name="SP_MAX_R" value="2400" unit="deg/s"/>
<define name="DEADBAND_P" value="10"/>
<define name="DEADBAND_Q" value="10"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="800"/>
<define name="GAIN_Q" value="800"/>
<define name="GAIN_R" value="700"/>
<define name="IGAIN_P" value="140"/>
<define name="IGAIN_Q" value="140"/>
<define name="IGAIN_R" value="90"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<define name="SP_MAX_PHI" value="50." unit="deg"/>
<define name="SP_MAX_THETA" value="50." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="2"/>
<define name="DEADBAND_E" value="2"/>
<define name="DEADBAND_R" value="100"/>
<define name="REF_OMEGA_P" value="800" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="800" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<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.)"/>
<define name="PHI_PGAIN" value="185"/>
<define name="PHI_DGAIN" value="70"/>
<define name="PHI_IGAIN" value="1"/>
<define name="THETA_PGAIN" value="185"/>
<define name="THETA_DGAIN" value="70"/>
<define name="THETA_IGAIN" value="1"/>
<define name="PSI_PGAIN" value="350"/>
<define name="PSI_DGAIN" value="100"/>
<define name="PSI_IGAIN" value="3"/>
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>
<!-- when using stabilization type float_quat use ones below, not tuned yet! -->
<!--
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<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_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<define name="REF_OMEGA_P" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_P" value="{0.85}"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="{RadOfDeg(400)}"/>
<define name="REF_ZETA_Q" value="{0.85}"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="{RadOfDeg(250)}"/>
<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.)"/>
<define name="PHI_PGAIN" value="{1000}"/>
<define name="PHI_DGAIN" value="{1000}"/>
<define name="PHI_IGAIN" value="{200}"/>
<define name="THETA_PGAIN" value="{1000}"/>
<define name="THETA_DGAIN" value="{1000}"/>
<define name="THETA_IGAIN" value="{200}"/>
<define name="PSI_PGAIN" value="{500}"/>
<define name="PSI_DGAIN" value="{500}"/>
<define name="PSI_IGAIN" value="{10}"/>
<define name="PHI_DGAIN_D" value="{100}"/>
<define name="THETA_DGAIN_D" value="{100}"/>
<define name="PSI_DGAIN_D" value="{100}"/>
<define name="PHI_DDGAIN" value="{300}"/>
<define name="THETA_DDGAIN" value="{300}"/>
<define name="PSI_DDGAIN" value="{300}"/>
</section>
-->
<!-- when using stabilization type indi use ones below, not tuned yet! -->
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.05"/>
<define name="G1_Q" value="0.025"/>
<define name="G1_R" value="0.0022"/>
<define name="G2_R" value="0.20"/>
<!-- For some airframes, e.g. 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="170.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="14.3"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!-- second order filter parameters -->
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>
<define name="FILT_CUTOFF_P" value="5.0"/>
<!-- first order actuator dynamics (indi_simple) -->
<define name="ACT_DYN_P" value="0.06"/>
<define name="ACT_DYN_Q" value="0.06"/>
<define name="ACT_DYN_R" value="0.06"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="TRUE"/>
<define name="ADAPTIVE_MU" value="0.0003"/>
<!--Maxium yaw rate, to avoid instability -->
<define name="MAX_R" value="120" unit="deg/s"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.33"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>
<section name="INS" prefix="INS_">
<!-- Use GPS altitude measurments and set the R gain -->
<define name="USE_GPS_ALT" value="1"/>
<define name="VFF_R_GPS" value="0.01"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value=" 0.51562740288882"/>
<define name="H_Y" value="-0.05707735220832"/>
<define name="H_Z" value=" 0.85490967783446"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="60." unit="deg"/>
<define name="USE_SPEED_REF" value="TRUE"/>
<define name="PGAIN" value="650"/>
<define name="DGAIN" value="350"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0" unit="m/s"/>
<define name="DESCEND_VSPEED" value="-0.7" unit="m/s"/>
</section>
<section name="MISC">
<define name="ARRIVED_AT_WAYPOINT" value="0.2" unit="m"/>
</section>
<!-- ********************** AP ************************** -->
<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_ATTITUDE_DIRECT"/><!-- if GNSS use AP_MODE_NAV ...-->
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_RATE_DIRECT"/><!-- for now...-->
<define name="MODE_AUTO2" value="AP_MODE_GUIDED"/> <!-- for dronerrace -->
<!-- <define name="MODE_AUTO2" value="AP_MODE_NAV"/>--> <!-- If GNSS device is added for autonomous flight -->
<!--<define name="USE_THROTTLE_FOR_MOTOR_ARMING" value="TRUE"/>-->
<define name="USE_KILL_SWITCH_FOR_MOTOR_ARMING" value="TRUE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<!-- If flying on a 2S1P 300mAh 40/80C LiPo -->
<section name="BAT">
<define name="MAX_BAT_CAPACITY" value="300" unit="mAh"/>
<!-- tested at V 7.6 the avg --> <!-- idle RPM then ?A half throttle ?A-->
<define name="MILLIAMP_AT_IDLE_THROTTLE" value="10" unit="mA"/> <!-- TODO ??mA, with additional RC receiver and wifi and jevois cam ~??mA -->
<define name="MILLIAMP_AT_FULL_THROTTLE" value="240" unit="mA"/> <!-- TODO At 7.2 ?? A at 8.2v ??A rounded then to ?? to be at safe side-->
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/> <!-- TODO: test when AP board switches off -->
<define name="CRITIC_BAT_LEVEL" value="6.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.7" unit="V"/> <!-- 2s LiPo HV 2x4.35 = 8.7 -->
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="FL, FR, BR, BL" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_quad" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
<!-- <define name="JS_AXIS_MODE" value="4"/>-->
</section>
<section name="GCS">
<define name="SPEECH_NAME" value="Trashcan"/>
<define name="AC_ICON" value="quadrotor_x"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="2"/> <!-- 2m low diff for e.g. optitrack, use e.g 10m for outside-->
<define name="ALT_SHIFT_PLUS" value="1" unit="m"/>
<define name="ALT_SHIFT_MINUS" value="-1" unit="m"/>
</section>
</airframe>
+61
View File
@@ -0,0 +1,61 @@
# Hey Emacs, this is a -*- makefile -*-
#
# crazybee_f4_1.0.makefile
#
# Take a look at https://www.openuas.org/ airframes for example
# Board is a crazybee F4 v1.0
BOARD=crazybee_f4
BOARD_VERSION=1.0
BOARD_CFG=\"boards/crazybee_f4_1.0.h\"
ARCH=stm32
ARCH_L=f4
ARCH_DIR=stm32
SRC_ARCH=arch/$(ARCH_DIR)
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/crazybee_f4_1.0.ld
HARD_FLOAT=yes
# Default flash mode is the STM32 DFU bootloader
# Theoreticlly possible are also SWD and JTAG_BMP
# But no simple physical connectors to the board...
# So... DFU it will be ...
FLASH_MODE?=DFU-UTIL
#idVendor=0483, idProduct=5740
#USB device strings: Mfr=1, Product=2, SerialNumber=3
#Product: Product: CrazyBee F4 (x)
#Manufacturer: Betaflight
#SerialNumber: 0x8000000
#TIP: ttyACM0: USB ACM device
#
# Default on PCB LED configuration
#
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= none
GPS_LED ?= none
SYS_TIME_LED ?= 1
#
# Default UART configuration (RC receiver, telemetry modem, GPS)
#
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2
RADIO_CONTROL_SBUS_PORT ?= UART2
MODEM_PORT ?= UART1
MODEM_BAUD ?= B115200
#
# GPS via I2C just as Baro and Magneto... sparec amount of uart ports left on this board
# If one starts using a build in RX on SPI Bus then TX1/RX1 can be used.
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# and by setting the correct "driver" attribute in servo section
ACTUATORS ?= actuators_pwm
+11
View File
@@ -197,4 +197,15 @@
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/guidance_hybrid.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml"
gui_color="blue"
/>
<aircraft
name="trashcan"
ac_id="1"
airframe="airframes/examples/trashcan.xml"
radio="radios/FrSky_Taranis_X9Dplus_TAERMK.xml"
telemetry="telemetry/default_rotorcraft_slow.xml"
flight_plan="flight_plans/dummy.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="[modules/gps.xml] [modules/ahrs_float_cmpl_quat.xml] [modules/ins_extended.xml] [modules/stabilization_int_quat.xml] [modules/nav_basic_rotorcraft.xml] [modules/guidance_rotorcraft.xml] [modules/imu_common.xml] modules/radio_control_cc2500_frsky.xml"
gui_color="blue"
/>
</conf>
+2
View File
@@ -61,6 +61,7 @@
<board name="openpilot_revo.*"/>
<board name="chimera_.*"/>
<board name="tawaki_.*"/>
<board name="crazybee_f4_.*"/>
<board name="crazyflie_.*"/>
</boards>
</mode>
@@ -76,6 +77,7 @@
<board name="openpilot_revo.*"/>
<board name="chimera_.*"/>
<board name="tawaki_.*"/>
<board name="crazybee_f4_.*"/>
<board name="crazyflie_.*"/>
</boards>
</mode>
+29
View File
@@ -0,0 +1,29 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="dfu_command" task="datalink"><!-- task="datalink" to run before telemetry_transparent_usb -->
<doc>
<description>
THIS MODULE MUST BE PLACED ABOVE ANY USB SERIAL CONSUMERS IN THE AIRFRAME!
Read USB serial for dfu command. Send '#\n', 'bl\n' to reset to DFU mode.
The same command works with betaflight (tested with 4.1.1), allowing
paparazzi to be uploaded directly to these boards.
The dfu command is automatically sent when uploading with DFU or DFU-UTIL
(see configure below).
</description>
</doc>
<header>
<file name="dfu_command.h"/>
</header>
<event fun="dfu_command_event()"/>
<makefile target="!fbw|sim|nps|hitl">
<configure name="SERIAL_TTY" default="/dev/ttyACM0"/>
<configure name="DFU_PRE_UPLOAD_CMD" default="@(printf '\043\012' > $(SERIAL_TTY) && sleep 1 && printf 'bl\012' > $(SERIAL_TTY) && sleep 1) || echo 'Warning: DFU command failed!'"/>
<configure name="DFU_UTIL_PRE_UPLOAD_CMD" default="@(printf '\043\012' > $(SERIAL_TTY) && sleep 1 && printf 'bl\012' > $(SERIAL_TTY) && sleep 1) || echo 'Warning: DFU command failed!'"/>
<define name="USE_USB_SERIAL"/>
<file name="dfu_command.c"/>
<file_arch name="usb_ser_hw.c" dir="."/>
</makefile>
</module>
@@ -0,0 +1,71 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="radio_control_cc2500_frsky" dir="radio_control/cc2500_frsky">
<doc>
<description>
Software implementation of Frsky radio control protocol for onboard CC2500 receiver.
</description>
<configure name="CC2500_SPI_DEV" value="SPIx" description="SPI device"/>
<configure name="CC2500_SPI_SLAVE_IDX" value="2" description="SPI slave index"/>
<define name="CC2500_GDO0_GPIO" value="GPIOC" description="GDO0 GPIO port"/>
<define name="CC2500_GDO0_PIN" value="GPIO14" description="GDO0 GPIO pin"/>
<define name="CC2500_RX_LED" value="LED_2|(undefined)" description="FrSky RX LED"/>
<define name="CC2500_BIND_BUTTON" value="BIND_BUTTON|(undefined)" description="GPIO button used to enter bind mode"/>
<define name="CC2500_RX_SPI_PROTOCOL" value="RX_SPI_FRSKY_X_LBT (default)|RX_SPI_FRSKY_X|RX_SPI_FRSKY_D" description="RX protocol"/>
<define name="CC2500_AUTOBIND" value="FALSE" description="Enter BIND mode at startup"/>
<define name="CC2500_TELEMETRY_SENSORS" value="(SENSOR_VOLTAGE | SENSOR_CURRENT | SENSOR_FUEL | SENSOR_ALTITUDE | SENSOR_VARIO)" description="List of sensors to send over FrSky telemetry (set to SENSOR_NONE) to disable."/>
</doc>
<settings>
<dl_settings>
<dl_settings NAME="cc2500_frsky">
<dl_setting var="cc2500_settings_persistent.bindVars" min="1" step="1" max="1" values="READ_ONLY" shortname="bindVars" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[0]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData0" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[1]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData1" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[2]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData2" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[3]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData3" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[4]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData4" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[5]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData5" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[6]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData6" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[7]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData7" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[8]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData8" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[9]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData9" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[10]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData10" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[11]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData11" persistent="true" type="uint32"/>
<dl_setting var="cc2500_settings_persistent.bindHopData[12]" min="1" step="1" max="1" values="READ_ONLY" shortname="bindHopData12" persistent="true" type="uint32"/>
</dl_settings>
</dl_settings>
</settings>
<header>
<file name="cc2500.h" dir="peripherals"/>
<file name="cc2500_paparazzi.h" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_settings.h" dir="subsystems/radio_control/cc2500_frsky"/>
</header>
<init fun="cc2500_init()"/>
<makefile target="ap|fbw|sim|nps">
<define name="RADIO_CONTROL_TYPE_H" value="subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.h" type="string"/>
<configure name="CC2500_SPI_DEV" default="SPI3" case="upper|lower"/>
<configure name="CC2500_SPI_SLAVE_IDX" default="2"/>
</makefile>
<makefile target="ap|fbw">
<define name="RADIO_CONTROL"/>
<define name="USE_$(CC2500_SPI_DEV)"/>
<define name="USE_SPI_SLAVE$(CC2500_SPI_SLAVE_IDX)"/>
<define name="CC2500_SPI_DEV" value="$(CC2500_SPI_DEV_LOWER)"/>
<define name="CC2500_SPI_SLAVE_IDX" value="$(CC2500_SPI_SLAVE_IDX)"/>
<file name="radio_control.c" dir="subsystems"/>
<file name="cc2500.c" dir="peripherals"/>
<file name="cc2500_paparazzi.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_settings.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_compat.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_common.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_rx.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_rx_spi.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_rx_spi_common.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_frsky_shared.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_frsky_x.c" dir="subsystems/radio_control/cc2500_frsky"/>
<file name="cc2500_smartport.c" dir="subsystems/radio_control/cc2500_frsky"/>
<raw>
include $(CFG_SHARED)/spi_master.makefile
</raw>
</makefile>
</module>
@@ -0,0 +1,66 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="telemetry_transparent_frsky_x" dir="datalink" task="datalink">
<doc>
<description>
Telemetry using pprzlink protocol over FrSky X SmartPort serial link
Downlink messages are sent on dataID 0x5015.
Uplink is not implemented yet.
Use the sw/tools/opentx-lua/sp2ser.lua script to receive these messages
on the TX and forward them to the USB port. The 'datalink' script can
read the pprzlink stream as a regular serial port.
The data rate is very limited (max ~160 bytes/s). The limitation comes
from the FrSky X protocol which can send at most 4 bytes of telemetry
every 9ms. Set CC2500_TELEMETRY_SENSORS (from radio_control_cc2500_frsky)
to SENSOR_NONE to maximize pprzlink throughput. Use a suitable telemetry
conf for this low data rate.
</description>
</doc>
<autoload name="telemetry" type="nps"/>
<autoload name="telemetry" type="sim"/>
<header>
<file name="pprz_dl.h"/>
<file name="frsky_x.h" dir="subsystems/datalink"/>
</header>
<init fun="datalink_frsky_x_init()"/>
<init fun="pprz_dl_init()"/>
<event fun="pprz_dl_event()"/>
<makefile>
<file name="frsky_x.c" dir="subsystems/datalink"/>
</makefile>
<makefile target="!fbw|sim|nps|hitl">
<define name="DOWNLINK"/>
<define name="PERIODIC_TELEMETRY"/>
<define name="USE_FRSKY_X_SERIAL"/>
<define name="DOWNLINK_DEVICE" value="frsky_x_serial"/>
<define name="PPRZ_UART" value="frsky_x_serial"/>
<define name="DOWNLINK_TRANSPORT" value="pprz_tp"/>
<define name="DATALINK" value="PPRZ"/>
<file name="pprz_dl.c"/>
<file name="downlink.c" dir="subsystems/datalink"/>
<file name="datalink.c" dir="subsystems/datalink"/>
<file name="telemetry.c" dir="subsystems/datalink"/>
<file name="pprz_transport.c" dir="pprzlink/src"/>
<file name="frsky_x.c" dir="subsystems/datalink"/>
</makefile>
<makefile target="ap" firmware="fixedwing">
<file name="fixedwing_datalink.c" dir="$(SRC_FIRMWARE)"/>
<file name="ap_downlink.c" dir="$(SRC_FIRMWARE)"/>
</makefile>
<makefile target="ap|fbw" firmware="fixedwing">
<file name="fbw_downlink.c" dir="$(SRC_FIRMWARE)"/>
</makefile>
<makefile target="ap" firmware="rotorcraft">
<file name="rotorcraft_datalink.c" dir="$(SRC_FIRMWARE)"/>
<file name="rotorcraft_telemetry.c" dir="$(SRC_FIRMWARE)"/>
</makefile>
<makefile target="ap" firmware="rover">
<file name="rover_datalink.c" dir="$(SRC_FIRMWARE)"/>
<file name="rover_telemetry.c" dir="$(SRC_FIRMWARE)"/>
</makefile>
</module>
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<!DOCTYPE radio SYSTEM "radio.dtd">
<radio name="FrSky Taranis X9Dplus TAERMK" data_min="988" data_max="2012" sync_min="6000" sync_max="18000" pulse_type="NEGATIVE">
<channel ctl="LeftStickVertical" function="THROTTLE" min="988" neutral="988" max="2012" average="0"/>
<channel ctl="RightStickHorizontal" function="ROLL" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="RightStickVertical" function="PITCH" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="LeftStickHorizontal" function="YAW" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="ModeSwitch" function="MODE" min="2012" neutral="1500" max="988" average="0"/>
<channel ctl="KillSwitch" function="KILL_SWITCH" min="2012" neutral="1500" max="988" average="0"/>
</radio>
+38
View File
@@ -0,0 +1,38 @@
/*
* Hey Emacs, this is a -*- makefile -*-
*
* Copyright (C) 2019 PPRZ team
*
* 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 Crazybee F4 (STM32F411CEU6), 512K FLASH flash, 128K RAM). */
/* FIXME: values possibly not correct
/* Define memory regions. */
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
/* Reserving 16kb flash (512-16=496) for persistent settings. */
rom (rx) : ORIGIN = 0x08000000, LENGTH = 496K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f4.ld
/* INCLUDE cortex-m-generic.ld */
+49 -1
View File
@@ -36,6 +36,8 @@
#include <libopencm3/stm32/timer.h>
#include <libopencm3/stm32/flash.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/stm32/rtc.h>
#include <libopencm3/stm32/pwr.h>
#include "std.h"
@@ -165,8 +167,55 @@ void rcc_clock_setup_in_hse_24mhz_out_24mhz_pprz(void)
}
#endif
#ifdef SYSTEM_MEMORY_BASE
void reset_to_dfu(void) {
// Request DFU at boot (init_dfu)
pwr_disable_backup_domain_write_protect();
RTC_BKPXR(0) = 0xFF;
pwr_enable_backup_domain_write_protect();
// Reset
scb_reset_system();
}
typedef void resetHandler_t(void);
typedef struct isrVector_s {
volatile uint32_t stackEnd;
resetHandler_t *resetHandler;
} isrVector_t;
static isrVector_t *system_isr_vector_table_base = (isrVector_t *) SYSTEM_MEMORY_BASE; // Find in ST AN2606. Defined in board header.
static void init_dfu(void) {
/* Reset to DFU if requested */
rcc_periph_clock_enable(RCC_RTC);
rcc_periph_clock_enable(RCC_PWR);
if (RTC_BKPXR(0) == 0xFF) {
// DFU request
// 0. Reset request
pwr_disable_backup_domain_write_protect();
RTC_BKPXR(0) = 0x00;
pwr_enable_backup_domain_write_protect();
// 1. Set MSP to system_isr_vector_table_base.stackEnd
// (betaflight system_stm32f4xx.c::75)
// (betaflight cmsis_armcc.h::226
register uint32_t __regMainStackPointer __asm("msp") __attribute__((unused)); // Note: declared unused to suppress gcc warning, not actually unused!
__regMainStackPointer = system_isr_vector_table_base->stackEnd; // = topOfMainStack;
// 2. system_isr_vector_table_base.resetHandler() (betaflight system_stm32f4xx.c::76)
system_isr_vector_table_base->resetHandler();
while (1);
}
}
#endif // SYSTEM_MEMORY_BASE
void mcu_arch_init(void)
{
#ifdef SYSTEM_MEMORY_BASE
init_dfu();
#endif
#if LUFTBOOT
PRINT_CONFIG_MSG("We are running luftboot, the interrupt vector is being relocated.")
#if defined STM32F4
@@ -222,7 +271,6 @@ void mcu_arch_init(void)
* FIXME is it really needed ?
*/
scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16);
}
#if defined(STM32F1)
+6
View File
@@ -31,8 +31,14 @@
#include "std.h"
#include BOARD_CONFIG
extern void mcu_arch_init(void);
#ifdef SYSTEM_MEMORY_BASE
extern void reset_to_dfu(void);
#endif
/* should probably not be here
* a couple of macros to use the rev instruction
+23
View File
@@ -64,6 +64,7 @@ static fifo_t rxfifo;
void fifo_init(fifo_t *fifo, uint8_t *buf);
bool fifo_put(fifo_t *fifo, uint8_t c);
bool fifo_get(fifo_t *fifo, uint8_t *pc);
bool fifo_peek(fifo_t *fifo, uint8_t *pc, uint8_t ofs);
int fifo_avail(fifo_t *fifo);
int fifo_free(fifo_t *fifo);
int tx_timeout; // tmp work around for usbd_ep_stall_get from, this function does not always seem to work
@@ -374,6 +375,15 @@ int fifo_free(fifo_t *fifo)
return (VCOM_FIFO_SIZE - 1 - fifo_avail(fifo));
}
bool fifo_peek(fifo_t *fifo, uint8_t *pc, uint8_t ofs) {
if (fifo_avail(fifo) < ofs + 1) {
return false;
}
int index = (fifo->tail + ofs) % VCOM_FIFO_SIZE;
*pc = fifo->buf[index];
return true;
}
/**
* Writes one character to VCOM port fifo.
@@ -420,6 +430,19 @@ int VCOM_getchar(void)
return result;
}
/**
* Reads one character from VCOM port without removing it from the queue
* @param ofs position to read
* @returns character read, or -1 if character could not be read
*/
int VCOM_peekchar(int ofs)
{
static int result = 0;
uint8_t c;
result = fifo_peek(&rxfifo, &c, ofs) ? c : -1;
return result;
}
/**
* Checks if buffer free in VCOM buffer
* @returns TRUE if len bytes are free
+309
View File
@@ -0,0 +1,309 @@
/* Since there is atm no schematic of the board, many pin to pin io was deducted
* by measuring on the PCB.
* Not all, e.g. the Volt and Current values are measured for the moment
* Would be great if one could determine the resitor bridge true values
*/
#ifndef CONFIG_CRAZYBEE_F4_1_0_H
#define CONFIG_CRAZYBEE_F4_1_0_H
#define BOARD_CRAZYBEE_F4_V1
/** System memory base - for DFU bootloader */
#define SYSTEM_MEMORY_BASE 0x1FFF0000
/** Clock config - STM32F4 - STM32F411CEU6 in 48 pin package UFQFPN48 **/
#define EXT_CLK 8000000 // 8mHz
#define AHB_CLK 84000000
/** LEDs **/
/* Green LED on flight controller */
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO GPIOC
#define LED_1_GPIO_PIN GPIO13
#define LED_1_GPIO_ON gpio_clear
#define LED_1_GPIO_OFF gpio_set
#define LED_1_AFIO_REMAP ((void)0)
/* Red/white RX LEDs */
/* Note: all LEDs are connected to a single pin */
#ifndef USE_LED_2
#define USE_LED_2 1
#endif
#define LED_2_GPIO GPIOB
#define LED_2_GPIO_PIN GPIO9
#define LED_2_GPIO_ON gpio_set
#define LED_2_GPIO_OFF gpio_clear
#define LED_2_AFIO_REMAP ((void)0)
/** UART's **/
/* UART1 */
#define UART1_GPIO_AF GPIO_AF7
#define UART1_GPIO_PORT_TX GPIOA
#define UART1_GPIO_TX GPIO9
#define UART1_GPIO_PORT_RX GPIOA
#define UART1_GPIO_RX GPIO10
/* UART2 */
//Can connect to built-in DSMX receiver is availabe on UART RX
//Not to be confused with DSMX over SPI, that is unrelated
#define UART2_GPIO_AF GPIO_AF7
#define UART2_GPIO_PORT_TX GPIOA
#define UART2_GPIO_TX GPIO2
#define UART2_GPIO_PORT_RX GPIOA
#define UART2_GPIO_RX GPIO3
/* SBUS inverted on UARTx is a separate physical pad on the board
* To be used for an receiverv that gives an inverted SBUS out signal */
/* FIXME: (re)setting UART based (e.g. Spektum) Serial RADIO_CONTROL_POWER_PORT
#define RADIO_CONTROL_POWER_PORT GPIOA
#define RADIO_CONTROL_POWER_PIN GPIO10
#define RADIO_CONTROL_POWER_ON gpio_clear // yes, inverted
#define RADIO_CONTROL_POWER_OFF gpio_set
*/
/* FIXME: Soft binding Spektrum */
/*
#define SPEKTRUM_UART2_RCC RCC_USART1 //But uard 2 if embedded CYRF chip Speksat can be on UART1
#define SPEKTRUM_UART2_BANK GPIOA
#define SPEKTRUM_UART2_PIN GPIO10
#define SPEKTRUM_UART2_AF GPIO_AF7
#define SPEKTRUM_UART2_IRQ NVIC_USART1_IRQ
#define SPEKTRUM_UART2_ISR usart1_isr
#define SPEKTRUM_UART2_DEV USART1
*/
/* FIXME to relate this to ifddefs of PPM config possibilities
*/
#ifndef USE_LED_STRIP
#define USE_LED_STRIP 1
#endif
#if USE_LED_STRIP
#define LED_STRIP_GPIO_PORT GPIOA
#define LED_STRIP_GPIO_PIN GPIO0
#endif
/* PPM
*
* FIXME: Default is PPM config 1, alternative 2 is CPPM input on RX2 pin but
* than no UART RX at the same time, but a need for that scenario is unlikely anyhow
*
* Originaly intended for 2812LED board - DMA1_ST2
* Can be re- used for input to connect a receiver that outputs CPPM pulsestrain
*/
#ifndef PPM_CONFIG
#define PPM_CONFIG 1
#endif
#ifdef PPM_CONFIG
#define USE_PPM_TIM5 1
#define PPM_CHANNEL TIM_IC1
#define PPM_TIMER_INPUT TIM_IC_IN_TI1
#define PPM_IRQ NVIC_TIM5_IRQ
//#define PPM_IRQ NVIC_TIM5_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 GPIO0
#define PPM_GPIO_AF GPIO_AF2
//#elif PPM_CONFIG == 2
///* RX SBUS/Spektumserial or CPPM input on PA3 (RX2 pin) */
//#define USE_PPM_TIM9 1
//#define PPM_CHANNEL TIM_IC2
//#define PPM_TIMER_INPUT TIM_IC_IN_TI2
//#define PPM_IRQ NVIC_TIM9_IRQ
//// Capture/Compare InteruptEnable and InterruptFlag
//#define PPM_CC_IE TIM_DIER_CC2IE
//#define PPM_CC_IF TIM_SR_CC2IF
//#define PPM_GPIO_PORT GPIOA
//#define PPM_GPIO_PIN GPIO3
//#define PPM_GPIO_AF GPIO_AF3
///* TODO: add option 3 of input on RX1 pin) */
//#else
//#error "Unknown PPM config"
#endif // PPM_CONFIG
/** SPI **/
/* SPI1 for MPU accel/gyro (MPU6000*/
#define SPI1_GPIO_AF GPIO_AF5
#define SPI1_GPIO_PORT_SCK GPIOA
#define SPI1_GPIO_SCK GPIO5
#define SPI1_GPIO_PORT_MISO GPIOA
#define SPI1_GPIO_MISO GPIO6
#define SPI1_GPIO_PORT_MOSI GPIOA
#define SPI1_GPIO_MOSI GPIO7
/* SPI slave pin declaration ACC_GYRO_CS on SPI1 ICM 20609-G*/
#define SPI_SELECT_SLAVE0_PORT GPIOA
#define SPI_SELECT_SLAVE0_PIN GPIO4
/* SPI2 for embedded OSD MAX chip*/
//#ifndef USE_MAX7456
//#define USE_MAX7456 0
//#endif
//#if USE_MAX7456
#define SPI2_GPIO_AF GPIO_AF5 //TODO check datasheet
#define SPI2_GPIO_PORT_SCK GPIOB
#define SPI2_GPIO_SCK GPIO13
#define SPI2_GPIO_PORT_MISO GPIOB
#define SPI2_GPIO_MISO GPIO14
#define SPI2_GPIO_PORT_MOSI GPIOB
#define SPI2_GPIO_MOSI GPIO15
/* SPI slave pin declaration OSD */
#define SPI_SELECT_SLAVE1_PORT GPIOB
#define SPI_SELECT_SLAVE1_PIN GPIO12
//#endif
/* Used SPI3 for RX direct, if RX solution is implemented in AP */
#define SPI3_GPIO_AF GPIO_AF6
#define SPI3_GPIO_PORT_SCK GPIOB
#define SPI3_GPIO_SCK GPIO3
#define SPI3_GPIO_PORT_MISO GPIOB
#define SPI3_GPIO_MISO GPIO4
#define SPI3_GPIO_PORT_MOSI GPIOB
#define SPI3_GPIO_MOSI GPIO5
/* SPI slave pin declaration for Receiver */
#define SPI_SELECT_SLAVE2_PORT GPIOA
#define SPI_SELECT_SLAVE2_PIN GPIO15
/* GDO0 pin for receiver */
#define CC2500_GDO0_GPIO GPIOC
#define CC2500_GDO0_PIN GPIO14
/* Bind button */
#define BIND_BUTTON_GPIO GPIOB
#define BIND_BUTTON_PIN GPIO2
/** Onboard ADCs **/
#define USE_AD_TIM1 1
/* Voltage */
#ifndef USE_ADC_1
#define USE_ADC_1 1
#endif
#if USE_ADC_1
#define AD1_1_CHANNEL 8
#define ADC_1 AD1_1
#define ADC_1_GPIO_PORT GPIOB
#define ADC_1_GPIO_PIN GPIO0
#define ADC_CHANNEL_VSUPPLY ADC_1
#define DefaultVoltageOfAdc(adc) (0.009*adc)// TODO: determine 100% correct value
#endif
/* Current */
#ifndef USE_ADC_2
#define USE_ADC_2 1
#endif
#if USE_ADC_2
#define AD1_2_CHANNEL 9
#define ADC_2 AD1_2
#define ADC_2_GPIO_PORT GPIOB
#define ADC_2_GPIO_PIN GPIO1
#define ADC_CHANNEL_CURRENT ADC_2
#define MilliAmpereOfAdc(adc)((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)// TODO: determine 100% correct value
#endif
/* TODO: Somehere on the board find PHiSICAL easily reachable I2C SDL SDA so to connect e.g. GNSS, Baro, Magneto
* TODO: Finish the I2C mapping if Pins found */
//#define I2C1_GPIO_AF GPIO_AF4
//#define I2C1_GPIO_PORT GPIOB
//#define I2C1_GPIO_SCL GPIO8
//#define I2C1_GPIO_SDA GPIO9
/* Default actuators driver */
#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
#define ActuatorsDefaultInit() ActuatorsPwmInit()
#define ActuatorsDefaultCommit() ActuatorsPwmCommit()
/* PWM */
#define PWM_USE_TIM2 1
#define PWM_USE_TIM4 1
#define USE_PWM1 1
#define USE_PWM2 1
#define USE_PWM3 1
#define USE_PWM4 1
/* ESC 1 (B10, TIM2, CH3)*/
#if USE_PWM1
#define PWM_SERVO_1 0
#define PWM_SERVO_1_TIMER TIM2
#define PWM_SERVO_1_GPIO GPIOB
#define PWM_SERVO_1_PIN GPIO10
#define PWM_SERVO_1_AF GPIO_AF1
#define PWM_SERVO_1_OC TIM_OC3
#define PWM_SERVO_1_OC_BIT (1<<2)
#else
#define PWM_SERVO_1_OC_BIT 0
#endif
/* ESC 2 (B6, TIM4, CH1)*/
#if USE_PWM2
#define PWM_SERVO_2 1
#define PWM_SERVO_2_TIMER TIM4
#define PWM_SERVO_2_GPIO GPIOB
#define PWM_SERVO_2_PIN GPIO6
#define PWM_SERVO_2_AF GPIO_AF2
#define PWM_SERVO_2_OC TIM_OC1
#define PWM_SERVO_2_OC_BIT (1<<0)
#else
#define PWM_SERVO_2_OC_BIT 0
#endif
/* ESC 3 (B7, TIM4, CH2) */
#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 GPIO7
#define PWM_SERVO_3_AF GPIO_AF2
#define PWM_SERVO_3_OC TIM_OC2
#define PWM_SERVO_3_OC_BIT (1<<1)
#else
#define PWM_SERVO_3_OC_BIT 0
#endif
/* ESC 4 (B8, TIM4, CH3) */
#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 GPIO8
#define PWM_SERVO_4_AF GPIO_AF2
#define PWM_SERVO_4_OC TIM_OC3
#define PWM_SERVO_4_OC_BIT (1<<2)
#else
#define PWM_SERVO_4_OC_BIT 0
#endif
#define PWM_TIM2_CHAN_MASK (PWM_SERVO_1_OC_BIT)
#define PWM_TIM4_CHAN_MASK (PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT)
/* Buzzer (C15, inverted) */
#if USE_BUZZER
#define PWM_BUZZER
#define PWM_BUZZER_GPIO GPIOC
#define PWM_BUZZER_PIN GPI15
#define PWM_BUZZER_GPIO_ON gpio_clear
#define PWM_BUZZER_GPIO_OFF gpio_set
#endif
#endif /* CONFIG_CRAZYBEE_F4_1_0_H */
+1
View File
@@ -42,6 +42,7 @@ extern struct usb_serial_periph usb_serial;
void VCOM_init(void);
int VCOM_putchar(int c);
int VCOM_getchar(void);
int VCOM_peekchar(int ofs);
bool VCOM_check_free_space(uint16_t len);
int VCOM_check_available(void);
void VCOM_set_linecoding(uint8_t mode);
+3
View File
@@ -32,6 +32,9 @@
#if USE_USB_SERIAL
#include "mcu_periph/usb_serial.h"
#endif
#if USE_FRSKY_X_SERIAL
#include "subsystems/datalink/frsky_x.h"
#endif
#if USE_UDP
#include "mcu_periph/udp.h"
#endif
@@ -0,0 +1,57 @@
/*
* Copyright (C) Tom van Dijk
*
* 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/dfu_command/dfu_command.c"
* @author Tom van Dijk
* Read USB serial for dfu command
*
* The reset_to_dfu() function needs to be implemented for the
* architecture in use. (sw/airborne/arch/.../mcu_arch.c)
*/
#include "modules/dfu_command/dfu_command.h"
#include "mcu_arch.h"
static const char dfu_command_str[] = "#\nbl\n"; // Note: same command resets betaflight to DFU
static int dfu_command_state = 0;
void dfu_command_event(void) {
// Search fifo for command string
for (int i = 0; i < VCOM_check_available(); ++i) {
if (VCOM_peekchar(i) == dfu_command_str[dfu_command_state]) {
dfu_command_state++;
if (dfu_command_str[dfu_command_state] == '\0') { // end of command string
reset_to_dfu();
}
} else {
dfu_command_state = 0;
}
}
// Prevent fifo blocking if bytes are not consumed by other process
if (!VCOM_check_free_space(1)) {
while (VCOM_check_available()) {
VCOM_getchar();
}
}
}
@@ -0,0 +1,34 @@
/*
* Copyright (C) Tom van Dijk
*
* 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/dfu_command/dfu_command.h"
* @author Tom van Dijk
* Read USB serial for dfu command
*/
#ifndef DFU_COMMAND_H
#define DFU_COMMAND_H
#include "mcu_periph/usb_serial.h"
void dfu_command_event(void);
#endif
+237
View File
@@ -0,0 +1,237 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* 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.
*/
#include "subsystems/datalink/downlink.h" // TODO remove before PR
#include "cc2500.h"
#include "generated/modules.h"
#include "mcu_periph/sys_time.h"
#include "mcu_periph/spi.h"
#include <assert.h>
#define USE_RX_CC2500
static struct spi_periph *cc2500_spi_p;
static struct spi_transaction cc2500_spi_t;
static uint8_t cc2500_input_buf[64];
static uint8_t cc2500_output_buf[64];
void cc2500_init(void) {
/* Set spi peripheral */
cc2500_spi_p = &(CC2500_SPI_DEV);
/* Set the spi transaction */
cc2500_spi_t.input_buf = cc2500_input_buf;
cc2500_spi_t.output_buf = cc2500_output_buf;
cc2500_spi_t.input_length = 0;
cc2500_spi_t.output_length = 0;
cc2500_spi_t.select = SPISelectUnselect;
cc2500_spi_t.cpol = SPICpolIdleLow;
cc2500_spi_t.cpha = SPICphaEdge1;
cc2500_spi_t.dss = SPIDss8bit;
cc2500_spi_t.bitorder = SPIMSBFirst;
cc2500_spi_t.cdiv = SPIDiv32; // Found experimentally
cc2500_spi_t.status = SPITransDone;
cc2500_spi_t.slave_idx = CC2500_SPI_SLAVE_IDX;
}
static void cc2500_delayMicroseconds(uint32_t us) {
float start = get_sys_time_float();
while(get_sys_time_float() < start + (us / 1.0e6)) ;
}
// Fix naming conflict with subsystems/radio_control/cc2500_frsky delayMicroseconds
#ifdef delayMicroseconds
#undef delayMicroseconds
#endif
#define delayMicroseconds(us) cc2500_delayMicroseconds(us)
static void rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length) {
// Check that the SPI transaction is not busy
assert(cc2500_spi_t.status == SPITransDone);
// Set up the transaction
cc2500_spi_t.output_length = 2; // command + commandData
cc2500_spi_t.input_length = length + 1; // STATUS BYTE + RETURN DATA
cc2500_spi_t.output_buf[0] = command;
cc2500_spi_t.output_buf[1] = commandData;
// Submit the transaction
spi_submit(cc2500_spi_p, &cc2500_spi_t);
// Spin until transaction is completed
while(cc2500_spi_t.status != SPITransSuccess) ; // TODO not ideal in event function...
cc2500_spi_t.status = SPITransDone;
// Copy the input buffer
for (uint8_t i = 0; i < length; ++i) {
retData[i] = cc2500_spi_t.input_buf[i + 1]; // Skips status byte, betaflight code does not work when this byte is included.
}
}
static uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData) {
uint8_t retData; // DATA
rxSpiReadCommandMulti(command, commandData, &retData, 1);
return retData;
}
static void rxSpiWriteCommandMulti(uint8_t command, uint8_t *data, uint8_t length) {
// Check that the SPI transaction is not busy
assert(cc2500_spi_t.status == SPITransDone);
// Set up the transaction
cc2500_spi_t.output_length = length + 1; // command + data[length]
cc2500_spi_t.input_length = 0;
cc2500_spi_t.output_buf[0] = command;
// Copy the data to the output buffer
for (uint8_t i = 0; i < length; ++i) {
cc2500_spi_t.output_buf[i + 1] = data[i];
}
// Submit the transaction
spi_submit(cc2500_spi_p, &cc2500_spi_t);
// Spin until transaction is completed
while(cc2500_spi_t.status != SPITransSuccess) ; // TODO not ideal in event function...
cc2500_spi_t.status = SPITransDone;
}
static void rxSpiWriteCommand(uint8_t command, uint8_t data) {
rxSpiWriteCommandMulti(command, &data, 1);
}
static void rxSpiWriteByte(uint8_t data) {
rxSpiWriteCommandMulti(data, NULL, 0);
}
// betaflight/src/main/drivers/rx/rx_cc2500.c @ 0a16f4d on Oct 1, 2018
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* CC2500 SPI drivers
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
//#include "platform.h"
#ifdef USE_RX_CC2500
//#include "build/build_config.h"
//
//#include "pg/rx.h"
//#include "pg/rx_spi.h"
//
//#include "drivers/io.h"
//#include "drivers/rx/rx_spi.h"
//#include "drivers/system.h"
//#include "drivers/time.h"
//#include "rx_cc2500.h"
#define NOP 0xFF
void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)
{
rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len);
// DOWNLINK_SEND_CC2500_PACKET(DefaultChannel, DefaultDevice,len, dpbuffer);
}
void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len)
{
cc2500Strobe(CC2500_SFTX); // 0x3B SFTX
rxSpiWriteCommandMulti(CC2500_3F_TXFIFO | CC2500_WRITE_BURST,
dpbuffer, len);
cc2500Strobe(CC2500_STX); // 0x35
}
void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
{
rxSpiReadCommandMulti(address, NOP, data, length);
}
void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length)
{
rxSpiWriteCommandMulti(address, data, length);
}
uint8_t cc2500ReadReg(uint8_t reg)
{
return rxSpiReadCommand(reg | 0x80, NOP);
}
void cc2500Strobe(uint8_t address) { rxSpiWriteByte(address); }
void cc2500WriteReg(uint8_t address, uint8_t data)
{
rxSpiWriteCommand(address, data);
}
void cc2500SetPower(uint8_t power)
{
const uint8_t patable[8] = {
0xC5, // -12dbm
0x97, // -10dbm
0x6E, // -8dbm
0x7F, // -6dbm
0xA9, // -4dbm
0xBB, // -2dbm
0xFE, // 0dbm
0xFF // 1.5dbm
};
if (power > 7)
power = 7;
cc2500WriteReg(CC2500_3E_PATABLE, patable[power]);
}
uint8_t cc2500Reset(void)
{
cc2500Strobe(CC2500_SRES);
delayMicroseconds(1000); // 1000us
// CC2500_SetTxRxMode(TXRX_OFF);
// RX_EN_off;//off tx
// TX_EN_off;//off rx
return cc2500ReadReg(CC2500_0E_FREQ1) == 0xC4; // check if reset
}
#endif
+207
View File
@@ -0,0 +1,207 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#ifndef PERIPHERALS_CC2500_H
#define PERIPHERALS_CC2500_H
void cc2500_init(void);
// betaflight/src/main/drivers/rx/rx_cc2500.h @ 0a16f4d on Oct 1, 2018
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
CC2500 SPI drivers
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
//#include "rx/rx_spi.h"
enum {
CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration
CC2500_01_IOCFG1 = 0x01, // GDO1 output pin configuration
CC2500_02_IOCFG0 = 0x02, // GDO0 output pin configuration
CC2500_03_FIFOTHR = 0x03, // RX FIFO and TX FIFO thresholds
CC2500_04_SYNC1 = 0x04, // Sync word, high byte
CC2500_05_SYNC0 = 0x05, // Sync word, low byte
CC2500_06_PKTLEN = 0x06, // Packet length
CC2500_07_PKTCTRL1 = 0x07, // Packet automation control
CC2500_08_PKTCTRL0 = 0x08, // Packet automation control
CC2500_09_ADDR = 0x09, // Device address
CC2500_0A_CHANNR = 0x0A, // Channel number
CC2500_0B_FSCTRL1 = 0x0B, // Frequency synthesizer control
CC2500_0C_FSCTRL0 = 0x0C, // Frequency synthesizer control
CC2500_0D_FREQ2 = 0x0D, // Frequency control word, high byte
CC2500_0E_FREQ1 = 0x0E, // Frequency control word, middle byte
CC2500_0F_FREQ0 = 0x0F, // Frequency control word, low byte
CC2500_10_MDMCFG4 = 0x10, // Modem configuration
CC2500_11_MDMCFG3 = 0x11, // Modem configuration
CC2500_12_MDMCFG2 = 0x12, // Modem configuration
CC2500_13_MDMCFG1 = 0x13, // Modem configuration
CC2500_14_MDMCFG0 = 0x14, // Modem configuration
CC2500_15_DEVIATN = 0x15, // Modem deviation setting
CC2500_16_MCSM2 = 0x16, // Main Radio Cntrl State Machine config
CC2500_17_MCSM1 = 0x17, // Main Radio Cntrl State Machine config
CC2500_18_MCSM0 = 0x18, // Main Radio Cntrl State Machine config
CC2500_19_FOCCFG = 0x19, // Frequency Offset Compensation config
CC2500_1A_BSCFG = 0x1A, // Bit Synchronization configuration
CC2500_1B_AGCCTRL2 = 0x1B, // AGC control
CC2500_1C_AGCCTRL1 = 0x1C, // AGC control
CC2500_1D_AGCCTRL0 = 0x1D, // AGC control
CC2500_1E_WOREVT1 = 0x1E, // High byte Event 0 timeout
CC2500_1F_WOREVT0 = 0x1F, // Low byte Event 0 timeout
CC2500_20_WORCTRL = 0x20, // Wake On Radio control
CC2500_21_FREND1 = 0x21, // Front end RX configuration
CC2500_22_FREND0 = 0x22, // Front end TX configuration
CC2500_23_FSCAL3 = 0x23, // Frequency synthesizer calibration
CC2500_24_FSCAL2 = 0x24, // Frequency synthesizer calibration
CC2500_25_FSCAL1 = 0x25, // Frequency synthesizer calibration
CC2500_26_FSCAL0 = 0x26, // Frequency synthesizer calibration
CC2500_27_RCCTRL1 = 0x27, // RC oscillator configuration
CC2500_28_RCCTRL0 = 0x28, // RC oscillator configuration
CC2500_29_FSTEST = 0x29, // Frequency synthesizer cal control
CC2500_2A_PTEST = 0x2A, // Production test
CC2500_2B_AGCTEST = 0x2B, // AGC test
CC2500_2C_TEST2 = 0x2C, // Various test settings
CC2500_2D_TEST1 = 0x2D, // Various test settings
CC2500_2E_TEST0 = 0x2E, // Various test settings
// Status registers
CC2500_30_PARTNUM = 0x30, // Part number
CC2500_31_VERSION = 0x31, // Current version number
CC2500_32_FREQEST = 0x32, // Frequency offset estimate
CC2500_33_LQI = 0x33, // Demodulator estimate for link quality
CC2500_34_RSSI = 0x34, // Received signal strength indication
CC2500_35_MARCSTATE = 0x35, // Control state machine state
CC2500_36_WORTIME1 = 0x36, // High byte of WOR timer
CC2500_37_WORTIME0 = 0x37, // Low byte of WOR timer
CC2500_38_PKTSTATUS = 0x38, // Current GDOx status and packet status
CC2500_39_VCO_VC_DAC = 0x39, // Current setting from PLL cal module
CC2500_3A_TXBYTES = 0x3A, // Underflow and # of bytes in TXFIFO
CC2500_3B_RXBYTES = 0x3B, // Overflow and # of bytes in RXFIFO
// Multi byte memory locations
CC2500_3E_PATABLE = 0x3E,
CC2500_3F_TXFIFO = 0x3F,
CC2500_3F_RXFIFO = 0x3F
};
// Definitions for burst/single access to registers
#define CC2500_WRITE_SINGLE 0x00
#define CC2500_WRITE_BURST 0x40
#define CC2500_READ_SINGLE 0x80
#define CC2500_READ_BURST 0xC0
// Strobe commands
#define CC2500_SRES 0x30 // Reset chip.
#define CC2500_SFSTXON \
0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1).
// If in RX/TX: Go to a wait state where only the synthesizer is
// running (for quick RX / TX turnaround).
#define CC2500_SXOFF 0x32 // Turn off crystal oscillator.
#define CC2500_SCAL 0x33 // Calibrate frequency synthesizer and turn it off
// (enables quick start).
#define CC2500_SRX \
0x34 // Enable RX. Perform calibration first if coming from IDLE and
// MCSM0.FS_AUTOCAL=1.
#define CC2500_STX \
0x35 // In IDLE state: Enable TX. Perform calibration first if
// MCSM0.FS_AUTOCAL=1. If in RX state and CCA is enabled:
// Only go to TX if channel is clear.
#define CC2500_SIDLE \
0x36 // Exit RX / TX, turn off frequency synthesizer and exit
// Wake-On-Radio mode if applicable.
#define CC2500_SAFC 0x37 // Perform AFC adjustment of the frequency synthesizer
#define CC2500_SWOR 0x38 // Start automatic RX polling sequence (Wake-on-Radio)
#define CC2500_SPWD 0x39 // Enter power down mode when CSn goes high.
#define CC2500_SFRX 0x3A // Flush the RX FIFO buffer.
#define CC2500_SFTX 0x3B // Flush the TX FIFO buffer.
#define CC2500_SWORRST 0x3C // Reset real time clock.
#define CC2500_SNOP \
0x3D // No operation. May be used to pad strobe commands to two
// bytes for simpler software.
//----------------------------------------------------------------------------------
// Chip Status Byte
//----------------------------------------------------------------------------------
// Bit fields in the chip status byte
#define CC2500_STATUS_CHIP_RDYn_BM 0x80
#define CC2500_STATUS_STATE_BM 0x70
#define CC2500_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F
// Chip states
#define CC2500_STATE_IDLE 0x00
#define CC2500_STATE_RX 0x10
#define CC2500_STATE_TX 0x20
#define CC2500_STATE_FSTXON 0x30
#define CC2500_STATE_CALIBRATE 0x40
#define CC2500_STATE_SETTLING 0x50
#define CC2500_STATE_RX_OVERFLOW 0x60
#define CC2500_STATE_TX_UNDERFLOW 0x70
//----------------------------------------------------------------------------------
// Other register bit fields
//----------------------------------------------------------------------------------
#define CC2500_LQI_CRC_OK_BM 0x80
#define CC2500_LQI_EST_BM 0x7F
void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len);
void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len);
void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length);
void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length);
uint8_t cc2500ReadReg(uint8_t reg);
void cc2500Strobe(uint8_t address);
void cc2500WriteReg(uint8_t address, uint8_t data);
void cc2500SetPower(uint8_t power);
uint8_t cc2500Reset(void);
#endif
+171
View File
@@ -0,0 +1,171 @@
/*
* Copyright (C) 2020 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#include "subsystems/radio_control/cc2500_frsky/cc2500_smartport.h"
#include "subsystems/datalink/frsky_x.h"
#include <string.h>
struct frsky_x_serial_periph frsky_x_serial;
/* Serial device */
// Based on usb_ser_hw.c
// Generic fifo implementation
static void fifo_init(fifo_t *fifo, uint8_t *buf, size_t size);
static bool fifo_put(fifo_t *fifo, uint8_t c);
static bool fifo_get(fifo_t *fifo, uint8_t *pc);
static int fifo_avail(fifo_t *fifo);
static int fifo_free(fifo_t *fifo);
static void fifo_init(fifo_t *fifo, uint8_t *buf, size_t size) {
fifo->head = 0;
fifo->tail = 0;
fifo->buf = buf;
fifo->size = size;
}
static bool fifo_put(fifo_t *fifo, uint8_t c) {
int next;
// check if FIFO has room
next = (fifo->head + 1) % fifo->size;
if (next == fifo->tail) {
// full
return false;
}
fifo->buf[fifo->head] = c;
fifo->head = next;
return true;
}
static bool fifo_get(fifo_t *fifo, uint8_t *pc) {
int next;
// check if FIFO has data
if (fifo->head == fifo->tail) {
return false;
}
next = (fifo->tail + 1) % fifo->size;
*pc = fifo->buf[fifo->tail];
fifo->tail = next;
return true;
}
static int fifo_avail(fifo_t *fifo) {
return (fifo->size + fifo->head - fifo->tail) % fifo->size;
}
static int fifo_free(fifo_t *fifo) {
return (fifo->size - 1 - fifo_avail(fifo));
}
// Serial device functions
static int frsky_x_serial_check_free_space(void *p, long *fd, uint16_t len);
static void frsky_x_serial_put_byte(void *p, long fd, uint8_t c);
static void frsky_x_serial_put_buffer(void *p, long fd, const uint8_t *data, uint16_t len);
static void frsky_x_serial_send_message(void *p, long fd);
static int frsky_x_serial_char_available(void *p);
static uint8_t frsky_x_serial_get_byte(void *p);
static int frsky_x_serial_check_free_space(void *p, long *fd, uint16_t len) {
(void) fd;
return (fifo_free(&((struct frsky_x_serial_periph *)p)->downlink_fifo) >= len ? true : false);
}
static void frsky_x_serial_put_byte(void *p, long fd, uint8_t c) {
(void) fd;
fifo_put(&((struct frsky_x_serial_periph *)p)->downlink_fifo, c);
}
static void frsky_x_serial_put_buffer(void *p, long fd, const uint8_t *data, uint16_t len) {
for (int i = 0; i < len; ++i) {
frsky_x_serial_put_byte(p, fd, data[i]);
}
}
static void frsky_x_serial_send_message(void *p, long fd) {
(void) p;
(void) fd;
/* Do nothing, handled by smartPortDownlink_cb */
}
static int frsky_x_serial_char_available(void *p) {
return fifo_avail(&((struct frsky_x_serial_periph *)p)->uplink_fifo);
}
static uint8_t frsky_x_serial_get_byte(void *p) {
uint8_t byte;
fifo_get(&((struct frsky_x_serial_periph *)p)->uplink_fifo, &byte);
return byte;
}
/* SmartPort sensor */
static bool smartPortDownlink_cb(uint32_t *data) {
if (fifo_avail(&frsky_x_serial.downlink_fifo) >= 4) {
uint8_t data_u8[4];
fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 0);
fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 1);
fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 2);
fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 3);
*data =
(data_u8[0] << 24) |
(data_u8[1] << 16) |
(data_u8[2] << 8) |
(data_u8[3]);
return true;
}
return false;
}
static void smartPortUplink_cb(smartPortPayload_t *payload) {
uint8_t shift = 24;
for (uint8_t i = 0; i < payload->frameId; ++i) {
fifo_put(&frsky_x_serial.uplink_fifo, (uint8_t)((payload->data >> shift) & 0xFF));
shift -= 8;
}
}
void datalink_frsky_x_init(void) {
/* Set up link device */
fifo_init(&frsky_x_serial.downlink_fifo, frsky_x_serial.downlink_buf, DOWNLINK_BUFFER_SIZE);
fifo_init(&frsky_x_serial.uplink_fifo, frsky_x_serial.uplink_buf, UPLINK_BUFFER_SIZE);
frsky_x_serial.device.periph = (void *)(&frsky_x_serial);
frsky_x_serial.device.check_free_space = frsky_x_serial_check_free_space;
frsky_x_serial.device.put_byte = frsky_x_serial_put_byte;
frsky_x_serial.device.put_buffer = frsky_x_serial_put_buffer;
frsky_x_serial.device.send_message = frsky_x_serial_send_message;
frsky_x_serial.device.char_available = frsky_x_serial_char_available;
frsky_x_serial.device.get_byte = frsky_x_serial_get_byte;
/* Attach to SmartPort hooks */
smartPortDownlink = smartPortDownlink_cb;
smartPortUplink = smartPortUplink_cb;
}
+51
View File
@@ -0,0 +1,51 @@
/*
* Copyright (C) 2020 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#ifndef DATALINK_FRSKY_X_H
#define DATALINK_FRSKY_X_H
#include "pprzlink/pprzlink_device.h"
#define DOWNLINK_BUFFER_SIZE 512
#define UPLINK_BUFFER_SIZE 512
typedef struct {
int head;
int tail;
uint8_t *buf;
size_t size;
} fifo_t;
struct frsky_x_serial_periph {
/** Generic device interface */
struct link_device device;
/* Downlink fifo */
fifo_t downlink_fifo;
uint8_t downlink_buf[DOWNLINK_BUFFER_SIZE];
/* Uplink fifo */
fifo_t uplink_fifo;
uint8_t uplink_buf[UPLINK_BUFFER_SIZE];
};
extern struct frsky_x_serial_periph frsky_x_serial;
void datalink_frsky_x_init(void);
#endif // DATALINK_FRSKY_X_H
@@ -0,0 +1,180 @@
#include "cc2500_compat.h"
#include "peripherals/cc2500.h"
#include "cc2500_settings.h"
#include "cc2500_common.h"
#include "cc2500_rx.h"
// betaflight/src/main/rx/cc2500_common.c @ 50bbe0b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
//#include "platform.h"
#if defined(USE_RX_FRSKY_SPI) || defined(USE_RX_SFHSS_SPI)
//#include "common/maths.h"
//
//#include "drivers/io.h"
//#include "drivers/rx/rx_cc2500.h"
//#include "drivers/time.h"
//
//#include "fc/config.h"
//
//#include "pg/pg.h"
//#include "pg/pg_ids.h"
//#include "pg/rx.h"
//#include "pg/rx_spi.h"
//#include "pg/rx_spi_cc2500.h"
//
//#include "rx/rx.h"
//#include "rx/rx_spi.h"
//
//#include "cc2500_common.h"
static IO_t gdoPin;
#if defined(USE_RX_CC2500_SPI_PA_LNA)
static IO_t txEnPin;
static IO_t rxLnaEnPin;
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
static IO_t antSelPin;
#endif
#endif
static int16_t rssiDbm;
uint16_t cc2500getRssiDbm(void)
{
return rssiDbm;
}
void cc2500setRssiDbm(uint8_t value)
{
if (value >= 128) {
rssiDbm = ((((uint16_t)value) * 18) >> 5) - 82;
} else {
rssiDbm = ((((uint16_t)value) * 18) >> 5) + 65;
}
setRssi(rssiDbm << 3, RSSI_SOURCE_RX_PROTOCOL);
}
bool cc2500getGdo(void)
{
return IORead(gdoPin);
}
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY)
void cc2500switchAntennae(void)
{
static bool alternativeAntennaSelected = true;
if (antSelPin) {
if (alternativeAntennaSelected) {
IOLo(antSelPin);
} else {
IOHi(antSelPin);
}
alternativeAntennaSelected = !alternativeAntennaSelected;
}
}
#endif
#if defined(USE_RX_CC2500_SPI_PA_LNA)
void cc2500TxEnable(void)
{
if (txEnPin) {
IOHi(txEnPin);
}
}
void cc2500TxDisable(void)
{
if (txEnPin) {
IOLo(txEnPin);
}
}
#endif
static bool cc2500SpiDetect(void)
{
const uint8_t chipPartNum = cc2500ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST); //CC2500 read registers chip part num
const uint8_t chipVersion = cc2500ReadReg(CC2500_31_VERSION | CC2500_READ_BURST); //CC2500 read registers chip version
if (chipPartNum == 0x80 && chipVersion == 0x03) {
return true;
}
return false;
}
bool cc2500SpiInit(void)
{
if (rxCc2500SpiConfig()->chipDetectEnabled && !cc2500SpiDetect()) {
return false;
}
// gpio init here
gdoPin = IOGetByTag(rxSpiConfig()->extiIoTag);
if (!gdoPin) {
return false;
}
IOInit(gdoPin, OWNER_RX_SPI_EXTI, 0);
IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
#if defined(USE_RX_CC2500_SPI_PA_LNA)
if (rxCc2500SpiConfig()->lnaEnIoTag) {
rxLnaEnPin = IOGetByTag(rxCc2500SpiConfig()->lnaEnIoTag);
IOInit(rxLnaEnPin, OWNER_RX_SPI_CC2500_LNA_EN, 0);
IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
IOHi(rxLnaEnPin); // always on at the moment
}
if (rxCc2500SpiConfig()->txEnIoTag) {
txEnPin = IOGetByTag(rxCc2500SpiConfig()->txEnIoTag);
IOInit(txEnPin, OWNER_RX_SPI_CC2500_TX_EN, 0);
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
} else {
txEnPin = IO_NONE;
}
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
if (rxCc2500SpiConfig()->antSelIoTag) {
antSelPin = IOGetByTag(rxCc2500SpiConfig()->antSelIoTag);
IOInit(antSelPin, OWNER_RX_SPI_CC2500_ANT_SEL, 0);
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
IOHi(antSelPin);
} else {
antSelPin = IO_NONE;
}
#endif
#endif // USE_RX_CC2500_SPI_PA_LNA
#if defined(USE_RX_CC2500_SPI_PA_LNA)
cc2500TxDisable();
#endif // USE_RX_CC2500_SPI_PA_LNA
if (rssiSource == RSSI_SOURCE_NONE) {
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
}
return true;
}
#endif
@@ -0,0 +1,40 @@
#include "cc2500_compat.h"
#include "cc2500_rx_spi.h"
// betaflight/src/main/rx/cc2500_common.h @ 50bbe0b on Jul 1
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "rx/rx_spi.h"
uint16_t cc2500getRssiDbm(void);
void cc2500setRssiDbm(uint8_t value);
bool cc2500getGdo(void);
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY)
void cc2500switchAntennae(void);
#endif
#if defined(USE_RX_CC2500_SPI_PA_LNA)
void cc2500TxEnable(void);
void cc2500TxDisable(void);
#endif
bool cc2500SpiInit(void);
@@ -0,0 +1,199 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* 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.
*/
#include "cc2500_compat.h"
#include "state.h"
#include "mcu_periph/adc.h"
#include "mcu_periph/gpio.h"
#include "mcu_periph/sys_time.h"
#include "subsystems/electrical.h"
#include <stdbool.h>
#include <assert.h>
#include <math.h>
// (unknown):
struct attitude_t bf_attitude = { { 0, 0, 0 } }; // Dummy values
// main/config/config.h:
struct pidProfile_s *currentPidProfile; // Dummy values
// main/config/feature.h:
bool bf_featureIsEnabled(const uint32_t mask) {
uint32_t features = FEATURE_RX_SPI | FEATURE_TELEMETRY;
return features & mask;
}
// main/common/filters.h:
#define M_PI_FLOAT 3.14159265358979323846f
float pt1FilterGain(float f_cut, float dT)
{
float RC = 1 / ( 2 * M_PI_FLOAT * f_cut);
return dT / (RC + dT);
}
void pt1FilterInit(pt1Filter_t *filter, float k) {
filter->state = 0.0f;
filter->k = k;
}
void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k) {
filter->k = k;
}
float pt1FilterApply(pt1Filter_t *filter, float input) {
filter->state = filter->state + filter->k * (input - filter->state);
return filter->state;
}
// main/drivers/time.h:
void bf_delayMicroseconds(timeUs_t us) {
sys_time_usleep(us);
}
void bf_delay(timeMs_t ms) {
bf_delayMicroseconds(ms * 1000);
}
timeUs_t bf_micros(void) {
return get_sys_time_usec();
}
timeMs_t bf_millis(void) {
return get_sys_time_msec();
}
// main/drivers/adc.h:
uint16_t bf_adcGetChannel(uint8_t channel) {
(void) channel;
// Return current, as voltage is already reported by getLegacyBatteryVoltage
return (uint16_t)(electrical.current * 10000.0); // Assumed in 0.1mA
}
// main/drivers/rx_spi.h:
bool bf_rxSpiDeviceInit(void) {
return TRUE;
}
// main/drivers/io.h:
IO_t bf_IOGetByTag(ioTag_t io) {
return (IO_t)io;
}
void bf_IOInit(IO_t io, uint8_t owner, uint8_t index) {
(void) io;
(void) owner;
(void) index;
}
void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg) {
if (!io) return;
switch(cfg) {
case IOCFG_OUT_PP:
gpio_setup_output(io->port, io->pin);
break;
case IOCFG_IN_FLOATING:
gpio_setup_input(io->port, io->pin);
break;
case IOCFG_IPU:
gpio_setup_input_pullup(io->port, io->pin);
break;
default:
assert("Invalid IO config" == NULL);
break;
}
}
bool bf_IORead(IO_t gpio) {
if (!gpio) return 0;
return gpio_get(gpio->port, gpio->pin);
}
void bf_IOHi(IO_t io) {
if (!io) return;
io->hi(io->port, io->pin);
}
void bf_IOLo(IO_t io) {
if (!io) return;
io->lo(io->port, io->pin);
}
void bf_IOToggle(IO_t io) {
if (!io) return;
gpio_toggle(io->port, io->pin);
}
// main/fc/controlrate_profile.h:
controlRateConfig_t *currentControlRateProfile; // Dummy values
// main/flight/position.h:
int32_t bf_getEstimatedAltitudeCm(void) {
return (int32_t)(stateGetPositionEnu_f()->z * 100.0);
}
int16_t bf_getEstimatedVario(void) {
return (int16_t)(stateGetSpeedEnu_f()->z * 100.0);
}
// main/sensors/battery.h
bool bf_isBatteryVoltageConfigured(void) {
return TRUE;
}
uint16_t bf_getLegacyBatteryVoltage(void) {
return (uint16_t)((electrical.vsupply * 100.0 + 5) / 10.0); // ???
}
uint16_t bf_getBatteryVoltage(void) {
return (uint16_t)(electrical.vsupply * 100.0); // 0.01V
}
uint8_t bf_getBatteryCellCount(void) {
return 0;
}
bool bf_isAmperageConfigured(void) {
return TRUE;
}
int32_t bf_getAmperage(void) {
return (int32_t)(electrical.current * 100.0);
}
int32_t bf_getMAhDrawn(void) {
return (int32_t)(electrical.charge * 1000.0);
}
@@ -0,0 +1,286 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* 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.
*/
/*
* This file contains compatibility code for the betaflight cc2500 frsky
* drivers.
*
* Notes:
* - Function macros are used so that betaflight names can be used when this
* header is included, while the actual functions can have a bf_ prefix to
* prevent possible name collisions.
*/
#ifndef RADIO_CONTROL_CC2500_COMPAT_H
#define RADIO_CONTROL_CC2500_COMPAT_H
#pragma GCC diagnostic ignored "-Wmissing-prototypes"
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
#pragma GCC diagnostic ignored "-Wswitch-default"
#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
#pragma GCC diagnostic ignored "-Wshadow"
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#define USE_RX_SPI
#define USE_RX_FRSKY_SPI
#define USE_RX_FRSKY_SPI_TELEMETRY
#if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X_LBT) || (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X)
#define USE_RX_FRSKY_SPI_X
#define USE_TELEMETRY_SMARTPORT
#endif
#if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_D)
#define USE_RX_FRSKY_SPI_D
#endif
#define DEBUG_SET(...) /* Do nothing */
#define STATIC_ASSERT(...) /* Do nothing */
#define STATIC_UNIT_TESTED static
// (unknown):
#define sensors(...) 1
struct attitude_values_t {
int8_t roll;
int8_t pitch;
int8_t yaw;
};
struct attitude_t {
struct attitude_values_t values;
};
extern struct attitude_t bf_attitude;
#define attitude bf_attitude
// main/common/utils.h:
#if __GNUC__ > 6
#define FALLTHROUGH __attribute__ ((fallthrough))
#else
#define FALLTHROUGH do {} while(0)
#endif
// main/common/time.h:
typedef int32_t timeDelta_t;
typedef uint32_t timeMs_t ;
typedef uint32_t timeUs_t;
#define TIMEUS_MAX UINT32_MAX
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }
// main/common/maths.h:
#define MIN(a,b) \
__extension__ ({ __typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
_a < _b ? _a : _b; })
// main/common/filter.h:
typedef struct pt1Filter_s {
float state;
float k;
} pt1Filter_t;
float pt1FilterGain(float f_cut, float dT);
void pt1FilterInit(pt1Filter_t *filter, float k);
void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k);
float pt1FilterApply(pt1Filter_t *filter, float input);
// main/config/config.h:
#define PID_ROLL 0
#define PID_PITCH 0
#define PID_YAW 0
struct pidGains_s {
uint8_t P;
uint8_t I;
uint8_t D;
};
struct pidProfile_s {
struct pidGains_s pid[1];
};
extern struct pidProfile_s *currentPidProfile;
// main/config/feature.h:
typedef enum {
FEATURE_RX_PPM = 1 << 0,
// FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
FEATURE_RX_SERIAL = 1 << 3,
// FEATURE_MOTOR_STOP = 1 << 4,
// FEATURE_SERVO_TILT = 1 << 5,
// FEATURE_SOFTSERIAL = 1 << 6,
// FEATURE_GPS = 1 << 7,
// FEATURE_RANGEFINDER = 1 << 9,
FEATURE_TELEMETRY = 1 << 10,
// FEATURE_3D = 1 << 12,
FEATURE_RX_PARALLEL_PWM = 1 << 13,
FEATURE_RX_MSP = 1 << 14,
FEATURE_RSSI_ADC = 1 << 15,
// FEATURE_LED_STRIP = 1 << 16,
// FEATURE_DASHBOARD = 1 << 17,
// FEATURE_OSD = 1 << 18,
// FEATURE_CHANNEL_FORWARDING = 1 << 20,
// FEATURE_TRANSPONDER = 1 << 21,
// FEATURE_AIRMODE = 1 << 22,
FEATURE_RX_SPI = 1 << 25,
// //FEATURE_SOFTSPI = 1 << 26, (removed)
// FEATURE_ESC_SENSOR = 1 << 27,
// FEATURE_ANTI_GRAVITY = 1 << 28,
// FEATURE_DYNAMIC_FILTER = 1 << 29,
} features_e;
bool bf_featureIsEnabled(const uint32_t mask);
#define featureIsEnabled(mask) bf_featureIsEnabled(mask)
// main/drivers/time.h:
void bf_delayMicroseconds(timeUs_t us);
#define delayMicroseconds(us) bf_delayMicroseconds(us)
void bf_delay(timeMs_t ms);
#define delay(ms) bf_delay(ms)
timeUs_t bf_micros(void);
#define micros() bf_micros()
timeMs_t bf_millis(void);
#define millis() bf_millis()
// main/drivers/adc.h:
#define ADC_EXTERNAL1 1
uint16_t bf_adcGetChannel(uint8_t channel);
#define adcGetChannel(channel) bf_adcGetChannel(channel)
// main/drivers/rx/rx_spi.h:
#define RX_SPI_MAX_PAYLOAD_SIZE 35
bool bf_rxSpiDeviceInit(void);
#define rxSpiDeviceInit(rxSpiConfig) bf_rxSpiDeviceInit()
// main/drivers/rx/rx_pwm.h:
#define PPM_RCVR_TIMEOUT 0
// main/drivers/io.h:
typedef void(*gpiofnptr_t)(uint32_t port, uint16_t pin);
struct gpio_t {
uint32_t port;
uint16_t pin;
gpiofnptr_t hi;
gpiofnptr_t lo;
};
typedef struct gpio_t *IO_t;
typedef IO_t ioTag_t;
#define IO_NONE NULL
IO_t bf_IOGetByTag(ioTag_t io);
#define IOGetByTag(io) bf_IOGetByTag(io)
void bf_IOInit(IO_t io, uint8_t owner, uint8_t index);
#define IOInit(io, owner, index) bf_IOInit(io, owner, index)
enum ioconfig_t {
IOCFG_OUT_PP,
IOCFG_IN_FLOATING,
IOCFG_IPU,
};
void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg);
#define IOConfigGPIO(io, cfg) bf_IOConfigGPIO(io, cfg)
bool bf_IORead(IO_t gpio);
#define IORead(gpio) bf_IORead(gpio)
void bf_IOHi(IO_t io);
#define IOHi(io) bf_IOHi(io)
void bf_IOLo(IO_t io);
#define IOLo(io) bf_IOLo(io)
void bf_IOToggle(IO_t io);
#define IOToggle(io) bf_IOToggle(io)
// main/fc/runtime_config.h:
#define isArmingDisabled() 0
#define ARMING_FLAG(...) 1
#define FLIGHT_MODE(...) 0
// main/fc/controlrate_profile.h:
#define FD_ROLL 0
#define FD_PITCH 0
#define FD_YAW 0
typedef struct {
uint8_t rates[1];
} controlRateConfig_t;
extern controlRateConfig_t *currentControlRateProfile;
// main/flight/position.h:
int32_t bf_getEstimatedAltitudeCm(void);
#define getEstimatedAltitudeCm() bf_getEstimatedAltitudeCm()
int16_t bf_getEstimatedVario(void);
#define getEstimatedVario() bf_getEstimatedVario()
// main/drivers/resources.h:
typedef enum {
OWNER_RX_SPI_EXTI,
OWNER_RX_SPI_BIND,
OWNER_LED,
} resourceOwner_e;
// main/sensors/battery.h
bool bf_isBatteryVoltageConfigured(void);
#define isBatteryVoltageConfigured() bf_isBatteryVoltageConfigured()
uint16_t bf_getLegacyBatteryVoltage(void);
#define getLegacyBatteryVoltage() bf_getLegacyBatteryVoltage()
uint16_t bf_getBatteryVoltage(void);
#define getBatteryVoltage() bf_getBatteryVoltage()
uint8_t bf_getBatteryCellCount(void);
#define getBatteryCellCount() bf_getBatteryCellCount()
bool bf_isAmperageConfigured(void);
#define isAmperageConfigured() bf_isAmperageConfigured()
int32_t bf_getAmperage(void);
#define getAmperage() bf_getAmperage()
int32_t bf_getMAhDrawn(void);
#define getMAhDrawn() bf_getMAhDrawn()
#endif // RADIO_CONTROL_CC2500_COMPAT_H
@@ -0,0 +1,32 @@
#include "cc2500_compat.h"
#include "cc2500_settings.h"
// betaflight/src/main/rx/cc2500_frsky_common.h @ 766c90b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "rx/rx_spi.h"
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet);
rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet);
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload);
@@ -0,0 +1,20 @@
/* TODO PLACEHOLDER CODE! */
#include "cc2500_compat.h"
#define RC_CHANNEL_COUNT_FRSKY_D 8
static rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const protocolState) {
(void) packet;
(void) protocolState;
return RX_SPI_RECEIVED_NONE;
}
static void frSkyDSetRcData(uint16_t *rcData, const uint8_t *payload) {
(void) rcData;
(void) payload;
return;
}
static void frSkyDInit(void) {
return;
}
@@ -0,0 +1,482 @@
#include "cc2500_compat.h"
#include "peripherals/cc2500.h"
#include "cc2500_settings.h"
#include "cc2500_rx_spi_common.h"
#include "cc2500_common.h"
#include "cc2500_frsky_common.h"
#include "cc2500_frsky_d.h"
#include "cc2500_frsky_x.h"
#include "cc2500_frsky_shared.h"
// betaflight/src/main/rx/cc2500_frsky_shared.c @ 766c90b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
//#include "platform.h"
#ifdef USE_RX_FRSKY_SPI
//#include "common/maths.h"
//
//#include "drivers/rx/rx_cc2500.h"
//#include "drivers/io.h"
//#include "drivers/time.h"
//
//#include "fc/config.h"
//
//#include "pg/rx.h"
//#include "pg/rx_spi.h"
//#include "pg/rx_spi_cc2500.h"
//
//#include "rx/rx.h"
//#include "rx/rx_spi.h"
//#include "rx/rx_spi_common.h"
//
//#include "rx/cc2500_common.h"
//#include "rx/cc2500_frsky_common.h"
//#include "rx/cc2500_frsky_d.h"
//#include "rx/cc2500_frsky_x.h"
//
//#include "cc2500_frsky_shared.h"
static rx_spi_protocol_e spiProtocol;
static timeMs_t start_time;
static uint8_t protocolState;
uint32_t missingPackets;
timeDelta_t timeoutUs;
static uint8_t calData[255][3];
static timeMs_t timeTunedMs;
uint8_t listLength;
static uint8_t bindIdx;
static int8_t bindOffset;
typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState);
typedef rx_spi_received_e processFrameFn(uint8_t * const packet);
typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload);
static handlePacketFn *handlePacket;
static processFrameFn *processFrame;
static setRcDataFn *setRcData;
static void initialise() {
cc2500Reset();
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
cc2500WriteReg(CC2500_18_MCSM0, 0x18);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04);
cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
cc2500WriteReg(CC2500_14_MDMCFG0, 0x7A);
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
cc2500WriteReg(CC2500_1A_BSCFG, 0x6C);
cc2500WriteReg(CC2500_1B_AGCCTRL2, 0x03);
cc2500WriteReg(CC2500_1C_AGCCTRL1, 0x40);
cc2500WriteReg(CC2500_1D_AGCCTRL0, 0x91);
cc2500WriteReg(CC2500_21_FREND1, 0x56);
cc2500WriteReg(CC2500_22_FREND0, 0x10);
cc2500WriteReg(CC2500_23_FSCAL3, 0xA9);
cc2500WriteReg(CC2500_24_FSCAL2, 0x0A);
cc2500WriteReg(CC2500_25_FSCAL1, 0x00);
cc2500WriteReg(CC2500_26_FSCAL0, 0x11);
cc2500WriteReg(CC2500_29_FSTEST, 0x59);
cc2500WriteReg(CC2500_2C_TEST2, 0x88);
cc2500WriteReg(CC2500_2D_TEST1, 0x31);
cc2500WriteReg(CC2500_2E_TEST0, 0x0B);
cc2500WriteReg(CC2500_03_FIFOTHR, 0x07);
cc2500WriteReg(CC2500_09_ADDR, 0x00);
switch (spiProtocol) {
case RX_SPI_FRSKY_D:
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
cc2500WriteReg(CC2500_06_PKTLEN, 0x19);
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05);
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
cc2500WriteReg(CC2500_10_MDMCFG4, 0xAA);
cc2500WriteReg(CC2500_11_MDMCFG3, 0x39);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x11);
cc2500WriteReg(CC2500_15_DEVIATN, 0x42);
break;
case RX_SPI_FRSKY_X:
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
cc2500WriteReg(CC2500_06_PKTLEN, 0x1E);
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A);
cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B);
cc2500WriteReg(CC2500_11_MDMCFG3, 0x61);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x13);
cc2500WriteReg(CC2500_15_DEVIATN, 0x51);
break;
case RX_SPI_FRSKY_X_LBT:
cc2500WriteReg(CC2500_17_MCSM1, 0x0E);
cc2500WriteReg(CC2500_0E_FREQ1, 0x80);
cc2500WriteReg(CC2500_0F_FREQ0, 0x00);
cc2500WriteReg(CC2500_06_PKTLEN, 0x23);
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B);
cc2500WriteReg(CC2500_11_MDMCFG3, 0xF8);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x03);
cc2500WriteReg(CC2500_15_DEVIATN, 0x53);
break;
default:
break;
}
for(unsigned c = 0;c < 0xFF; c++)
{ //calibrate all channels
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_0A_CHANNR, c);
cc2500Strobe(CC2500_SCAL);
delayMicroseconds(900); //
calData[c][0] = cc2500ReadReg(CC2500_23_FSCAL3);
calData[c][1] = cc2500ReadReg(CC2500_24_FSCAL2);
calData[c][2] = cc2500ReadReg(CC2500_25_FSCAL1);
}
}
void initialiseData(bool inBindState)
{
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)rxCc2500SpiConfig()->bindOffset);
cc2500WriteReg(CC2500_18_MCSM0, 0x8);
cc2500WriteReg(CC2500_09_ADDR, inBindState ? 0x03 : rxCc2500SpiConfig()->bindTxId[0]);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0D);
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
if (!inBindState) {
cc2500WriteReg(CC2500_03_FIFOTHR, 0x14);
}
delay(10);
}
static void initTuneRx(void)
{
cc2500WriteReg(CC2500_19_FOCCFG, 0x14);
timeTunedMs = millis();
bindOffset = -126;
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0C);
cc2500WriteReg(CC2500_18_MCSM0, 0x8);
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]);
cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]);
cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]);
cc2500WriteReg(CC2500_0A_CHANNR, 0);
cc2500Strobe(CC2500_SFRX);
cc2500Strobe(CC2500_SRX);
}
static bool tuneRx(uint8_t *packet)
{
if (bindOffset >= 126) {
bindOffset = -126;
}
if ((millis() - timeTunedMs) > 50) {
timeTunedMs = millis();
bindOffset += 5;
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
}
if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
uint8_t Lqi = packet[ccLen - 1] & 0x7F;
// higher lqi represent better link quality
if (Lqi > 50) {
rxCc2500SpiConfigMutable()->bindOffset = bindOffset;
return true;
}
}
}
}
}
return false;
}
static void initGetBind(void)
{
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]);
cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]);
cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]);
cc2500WriteReg(CC2500_0A_CHANNR, 0);
cc2500Strobe(CC2500_SFRX);
delayMicroseconds(20); // waiting flush FIFO
cc2500Strobe(CC2500_SRX);
listLength = 0;
bindIdx = 0x05;
}
static bool getBind1(uint8_t *packet)
{
// len|bind |tx
// id|03|01|idx|h0|h1|h2|h3|h4|00|00|00|00|00|00|00|00|00|00|00|00|00|00|00|CHK1|CHK2|RSSI|LQI/CRC|
// Start by getting bind packet 0 and the txid
if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
if (packet[5] == 0x00) {
rxCc2500SpiConfigMutable()->bindTxId[0] = packet[3];
rxCc2500SpiConfigMutable()->bindTxId[1] = packet[4];
for (uint8_t n = 0; n < 5; n++) {
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] =
packet[6 + n];
}
rxCc2500SpiConfigMutable()->rxNum = packet[12];
return true;
}
}
}
}
}
return false;
}
static bool getBind2(uint8_t *packet)
{
if (bindIdx <= 120) {
if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
if ((packet[3] == rxCc2500SpiConfig()->bindTxId[0]) &&
(packet[4] == rxCc2500SpiConfig()->bindTxId[1])) {
if (packet[5] == bindIdx) {
#if defined(DJTS)
if (packet[5] == 0x2D) {
for (uint8_t i = 0; i < 2; i++) {
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i];
}
listLength = 47;
return true;
}
#endif
for (uint8_t n = 0; n < 5; n++) {
if (packet[6 + n] == packet[ccLen - 3] || (packet[6 + n] == 0)) {
if (bindIdx >= 0x2D) {
listLength = packet[5] + n;
return true;
}
}
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
}
bindIdx = bindIdx + 5;
return false;
}
}
}
}
}
}
return false;
} else {
return true;
}
}
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
{
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
switch (protocolState) {
case STATE_INIT:
if ((millis() - start_time) > 10) {
initialise();
protocolState = STATE_BIND;
}
break;
case STATE_BIND:
if (rxSpiCheckBindRequested(true) || rxCc2500SpiConfig()->autoBind) {
rxSpiLedOn();
initTuneRx();
protocolState = STATE_BIND_TUNING;
} else {
protocolState = STATE_STARTING;
}
break;
case STATE_BIND_TUNING:
if (tuneRx(packet)) {
initGetBind();
initialiseData(true);
protocolState = STATE_BIND_BINDING1;
}
break;
case STATE_BIND_BINDING1:
if (getBind1(packet)) {
protocolState = STATE_BIND_BINDING2;
}
break;
case STATE_BIND_BINDING2:
if (getBind2(packet)) {
cc2500Strobe(CC2500_SIDLE);
protocolState = STATE_BIND_COMPLETE;
}
break;
case STATE_BIND_COMPLETE:
if (!rxCc2500SpiConfig()->autoBind) {
writeEEPROM();
} else {
uint8_t ctr = 80;
while (ctr--) {
rxSpiLedToggle();
delay(50);
}
}
ret = RX_SPI_RECEIVED_BIND;
protocolState = STATE_STARTING;
break;
default:
ret = handlePacket(packet, &protocolState);
break;
}
return ret;
}
rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet)
{
if (processFrame) {
return processFrame(packet);
}
return RX_SPI_RECEIVED_NONE;
}
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload)
{
setRcData(rcData, payload);
}
void nextChannel(uint8_t skip)
{
static uint8_t channr = 0;
channr += skip;
while (channr >= listLength) {
channr -= listLength;
}
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3,
calData[rxCc2500SpiConfig()->bindHopData[channr]][0]);
cc2500WriteReg(CC2500_24_FSCAL2,
calData[rxCc2500SpiConfig()->bindHopData[channr]][1]);
cc2500WriteReg(CC2500_25_FSCAL1,
calData[rxCc2500SpiConfig()->bindHopData[channr]][2]);
cc2500WriteReg(CC2500_0A_CHANNR, rxCc2500SpiConfig()->bindHopData[channr]);
if (spiProtocol == RX_SPI_FRSKY_D) {
cc2500Strobe(CC2500_SFRX);
}
}
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
rxSpiCommonIOInit(rxSpiConfig);
if (!cc2500SpiInit()) {
return false;
}
spiProtocol = rxSpiConfig->rx_spi_protocol;
switch (spiProtocol) {
case RX_SPI_FRSKY_D:
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_D;
handlePacket = frSkyDHandlePacket;
setRcData = frSkyDSetRcData;
frSkyDInit();
break;
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
handlePacket = frSkyXHandlePacket;
#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
processFrame = frSkyXProcessFrame;
#endif
setRcData = frSkyXSetRcData;
frSkyXInit(spiProtocol);
break;
default:
break;
}
#if defined(USE_RX_FRSKY_SPI_TELEMETRY)
if (rssiSource == RSSI_SOURCE_NONE) {
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
}
#endif
missingPackets = 0;
timeoutUs = 50;
start_time = millis();
protocolState = STATE_INIT;
return true;
}
#endif
@@ -0,0 +1,57 @@
// betaflight/src/main/rx/cc2500_frsky_shared.h @ cb66ee0
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "rx/rx_spi.h"
#define MAX_MISSING_PKT 100
#define DEBUG_DATA_ERROR_COUNT 0
#define DEBUG_DATA_MISSING_PACKETS 1
#define DEBUG_DATA_BAD_FRAME 2
#define SYNC_DELAY_MAX 9000
#define MAX_MISSING_PKT 100
enum {
STATE_INIT = 0,
STATE_BIND,
STATE_BIND_TUNING,
STATE_BIND_BINDING1,
STATE_BIND_BINDING2,
STATE_BIND_COMPLETE,
STATE_STARTING,
STATE_UPDATE,
STATE_DATA,
STATE_TELEMETRY,
STATE_RESUME,
};
extern uint8_t listLength;
extern uint32_t missingPackets;
extern timeDelta_t timeoutUs;
void initialiseData(bool inBindState);
void nextChannel(uint8_t skip);
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,35 @@
#include "cc2500_compat.h"
// betaflight/src/main/rx/cc2500_frsky_x.h @ 766c90b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "rx/rx.h"
//#include "rx/rx_spi.h"
#define RC_CHANNEL_COUNT_FRSKY_X 16
void frSkyXSetRcData(uint16_t *rcData, const uint8_t *payload);
void frSkyXInit(const rx_spi_protocol_e spiProtocol);
rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState);
rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet);
@@ -0,0 +1,77 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#include "cc2500_paparazzi.h"
#include "subsystems/radio_control.h"
#include "peripherals/cc2500.h"
#include "cc2500_common.h"
#include "cc2500_frsky_common.h"
#include "cc2500_settings.h"
#include "cc2500_rx.h"
#include <stdint.h>
static uint16_t frsky_raw[RADIO_CTL_NB];
#if PERIODIC_TELEMETRY
#include "subsystems/datalink/telemetry.h"
static void send_cc2500_ppm(struct transport_tx *trans, struct link_device *dev)
{
pprz_msg_send_PPM(trans, dev, AC_ID,
&radio_control.frame_rate,
(sizeof(frsky_raw) / sizeof(frsky_raw[0])),
frsky_raw);
}
#endif
void radio_control_impl_init(void) {
cc2500_settings_init();
cc2500_init();
cc2500Reset();
rxInit();
#if PERIODIC_TELEMETRY
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_PPM, send_cc2500_ppm);
#endif
}
void radio_control_impl_event(void (* _received_frame_handler)(void)) {
if (rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig) & RX_FRAME_COMPLETE) {
rxRuntimeConfig.rcProcessFrameFn(&rxRuntimeConfig);
radio_control.frame_cpt++;
radio_control.time_since_last_frame = 0;
if (radio_control.radio_ok_cpt > 0) {
radio_control.radio_ok_cpt--;
} else {
radio_control.status = RC_OK;
for (int i = 0; i < RADIO_CONTROL_NB_CHANNEL; ++i) {
frsky_raw[i] = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i);
}
NormalizePpmIIR(frsky_raw, radio_control);
_received_frame_handler();
}
}
}
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#ifndef RADIO_CONTROL_CC2500_PAPARAZZI_H
#define RADIO_CONTROL_CC2500_PAPARAZZI_H
#define RC_PPM_TICKS_OF_USEC(_x) (_x)
#define RC_PPM_SIGNED_TICKS_OF_USEC(_x) (_x)
#define USEC_OF_RC_PPM_TICKS(_x) (_x)
#include "generated/airframe.h"
#include "generated/radio.h"
#ifndef RADIO_CONTROL_NB_CHANNEL
#define RADIO_CONTROL_NB_CHANNEL RADIO_CTL_NB
#endif
extern void radio_control_impl_event(void (* _received_frame_handler)(void));
#define RadioControlEvent(_received_frame_handler) radio_control_impl_event(_received_frame_handler)
#endif // RADIO_CONTROL_CC2500_PAPARAZZI_H
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,211 @@
#include "cc2500_compat.h"
// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT!
// betaflight/src/main/rx/rx.h @ 4e8249e
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "common/time.h"
//
//#include "pg/pg.h"
//#include "pg/rx.h"
//
//#include "drivers/io_types.h"
//
//#define STICK_CHANNEL_COUNT 4
//
//#define PWM_RANGE_MIN 1000
//#define PWM_RANGE_MAX 2000
//#define PWM_RANGE_MIDDLE (PWM_RANGE_MIN + ((PWM_RANGE_MAX - PWM_RANGE_MIN) / 2))
//
//#define PWM_PULSE_MIN 750 // minimum PWM pulse width which is considered valid
//#define PWM_PULSE_MAX 2250 // maximum PWM pulse width which is considered valid
//
//#define RXFAIL_STEP_TO_CHANNEL_VALUE(step) (PWM_PULSE_MIN + 25 * step)
//#define CHANNEL_VALUE_TO_RXFAIL_STEP(channelValue) ((constrain(channelValue, PWM_PULSE_MIN, PWM_PULSE_MAX) - PWM_PULSE_MIN) / 25)
//#define MAX_RXFAIL_RANGE_STEP ((PWM_PULSE_MAX - PWM_PULSE_MIN) / 25)
//
//#define DEFAULT_SERVO_MIN 1000
//#define DEFAULT_SERVO_MIDDLE 1500
//#define DEFAULT_SERVO_MAX 2000
typedef enum {
RX_FRAME_PENDING = 0,
RX_FRAME_COMPLETE = (1 << 0),
RX_FRAME_FAILSAFE = (1 << 1),
RX_FRAME_PROCESSING_REQUIRED = (1 << 2),
RX_FRAME_DROPPED = (1 << 3)
} rxFrameState_e;
typedef enum {
SERIALRX_SPEKTRUM1024 = 0,
SERIALRX_SPEKTRUM2048 = 1,
SERIALRX_SBUS = 2,
SERIALRX_SUMD = 3,
SERIALRX_SUMH = 4,
SERIALRX_XBUS_MODE_B = 5,
SERIALRX_XBUS_MODE_B_RJ01 = 6,
SERIALRX_IBUS = 7,
SERIALRX_JETIEXBUS = 8,
SERIALRX_CRSF = 9,
SERIALRX_SRXL = 10,
SERIALRX_TARGET_CUSTOM = 11,
SERIALRX_FPORT = 12,
SERIALRX_SRXL2 = 13,
} SerialRXType;
//#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 12
//#define MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT 8
#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18
#define NON_AUX_CHANNEL_COUNT 4
#define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT)
//#if MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT > MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
//#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT
//#else
//#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
//#endif
//
//extern const char rcChannelLetters[];
//
//extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
//
//#define RSSI_SCALE_MIN 1
//#define RSSI_SCALE_MAX 255
//
//#define RSSI_SCALE_DEFAULT 100
//
//typedef enum {
// RX_FAILSAFE_MODE_AUTO = 0,
// RX_FAILSAFE_MODE_HOLD,
// RX_FAILSAFE_MODE_SET,
// RX_FAILSAFE_MODE_INVALID
//} rxFailsafeChannelMode_e;
//
//#define RX_FAILSAFE_MODE_COUNT 3
//
//typedef enum {
// RX_FAILSAFE_TYPE_FLIGHT = 0,
// RX_FAILSAFE_TYPE_AUX
//} rxFailsafeChannelType_e;
//
//#define RX_FAILSAFE_TYPE_COUNT 2
//
//typedef struct rxFailsafeChannelConfig_s {
// uint8_t mode; // See rxFailsafeChannelMode_e
// uint8_t step;
//} rxFailsafeChannelConfig_t;
//
//PG_DECLARE_ARRAY(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs);
//
//typedef struct rxChannelRangeConfig_s {
// uint16_t min;
// uint16_t max;
//} rxChannelRangeConfig_t;
//
//PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
struct rxRuntimeConfig_s;
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
typedef uint8_t (*rcFrameStatusFnPtr)(struct rxRuntimeConfig_s *rxRuntimeConfig);
typedef bool (*rcProcessFrameFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig);
typedef enum {
RX_PROVIDER_NONE = 0,
RX_PROVIDER_PARALLEL_PWM,
RX_PROVIDER_PPM,
RX_PROVIDER_SERIAL,
RX_PROVIDER_MSP,
RX_PROVIDER_SPI,
} rxProvider_t;
typedef struct rxRuntimeConfig_s {
rxProvider_t rxProvider;
SerialRXType serialrxProvider;
uint8_t channelCount; // number of RC channels as reported by current input driver
uint16_t rxRefreshRate;
rcReadRawDataFnPtr rcReadRawFn;
rcFrameStatusFnPtr rcFrameStatusFn;
rcProcessFrameFnPtr rcProcessFrameFn;
uint16_t *channelData;
void *frameData;
} rxRuntimeConfig_t;
typedef enum {
RSSI_SOURCE_NONE = 0,
RSSI_SOURCE_ADC,
RSSI_SOURCE_RX_CHANNEL,
RSSI_SOURCE_RX_PROTOCOL,
RSSI_SOURCE_MSP,
RSSI_SOURCE_FRAME_ERRORS,
RSSI_SOURCE_RX_PROTOCOL_CRSF,
} rssiSource_e;
extern rssiSource_e rssiSource;
//typedef enum {
// LQ_SOURCE_NONE = 0,
// LQ_SOURCE_RX_PROTOCOL_CRSF,
//} linkQualitySource_e;
//
//extern linkQualitySource_e linkQualitySource;
extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
void rxInit(void);
//bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs);
//bool rxIsReceivingSignal(void);
//bool rxAreFlightChannelsValid(void);
//bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
//
//struct rxConfig_s;
//
//void parseRcChannels(const char *input, struct rxConfig_s *rxConfig);
//
//#define RSSI_MAX_VALUE 1023
void setRssiDirect(uint16_t newRssi, rssiSource_e source);
void setRssi(uint16_t rssiValue, rssiSource_e source);
//void setRssiMsp(uint8_t newMspRssi);
//void updateRSSI(timeUs_t currentTimeUs);
//uint16_t getRssi(void);
//uint8_t getRssiPercent(void);
//bool isRssiConfigured(void);
//
//#define LINK_QUALITY_MAX_VALUE 1023
//
//uint16_t rxGetLinkQuality(void);
//void setLinkQualityDirect(uint16_t linkqualityValue);
//uint16_t rxGetLinkQualityPercent(void);
//
//uint8_t getRssiDbm(void);
//void setRssiDbm(uint8_t newRssiDbm, rssiSource_e source);
//void setRssiDbmDirect(uint8_t newRssiDbm, rssiSource_e source);
//
//void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);
//
//void suspendRxPwmPpmSignal(void);
//void resumeRxPwmPpmSignal(void);
//
//uint16_t rxGetRefreshRate(void);
@@ -0,0 +1,248 @@
#include "cc2500_compat.h"
#include "cc2500_settings.h"
#include "cc2500_rx_spi.h"
#include "cc2500_frsky_common.h"
#define UNUSED(x) (void)(x)
// betaflight/src/main/rx/rx_spi.c @ 766c90b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
//#include "platform.h"
#ifdef USE_RX_SPI
//#include "build/build_config.h"
//
//#include "common/utils.h"
//
//#include "config/feature.h"
//
//#include "drivers/rx/rx_spi.h"
//#include "drivers/rx/rx_nrf24l01.h"
//
//#include "fc/config.h"
//
//#include "pg/rx_spi.h"
//
//#include "rx/rx_spi.h"
//#include "rx/cc2500_frsky_common.h"
//#include "rx/nrf24_cx10.h"
//#include "rx/nrf24_syma.h"
//#include "rx/nrf24_v202.h"
//#include "rx/nrf24_h8_3d.h"
//#include "rx/nrf24_inav.h"
//#include "rx/nrf24_kn.h"
//#include "rx/a7105_flysky.h"
//#include "rx/cc2500_sfhss.h"
//#include "rx/cyrf6936_spektrum.h"
uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
STATIC_UNIT_TESTED uint8_t rxSpiPayload[RX_SPI_MAX_PAYLOAD_SIZE];
STATIC_UNIT_TESTED uint8_t rxSpiNewPacketAvailable; // set true when a new packet is received
typedef bool (*protocolInitFnPtr)(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
typedef rx_spi_received_e (*protocolDataReceivedFnPtr)(uint8_t *payload);
typedef rx_spi_received_e (*protocolProcessFrameFnPtr)(uint8_t *payload);
typedef void (*protocolSetRcDataFromPayloadFnPtr)(uint16_t *rcData, const uint8_t *payload);
static protocolInitFnPtr protocolInit;
static protocolDataReceivedFnPtr protocolDataReceived;
static protocolProcessFrameFnPtr protocolProcessFrame;
static protocolSetRcDataFromPayloadFnPtr protocolSetRcDataFromPayload;
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
{
STATIC_ASSERT(NRF24L01_MAX_PAYLOAD_SIZE <= RX_SPI_MAX_PAYLOAD_SIZE, NRF24L01_MAX_PAYLOAD_SIZE_larger_than_RX_SPI_MAX_PAYLOAD_SIZE);
if (channel >= rxRuntimeConfig->channelCount) {
return 0;
}
if (rxSpiNewPacketAvailable) {
protocolSetRcDataFromPayload(rxSpiRcData, rxSpiPayload);
rxSpiNewPacketAvailable = false;
}
return rxSpiRcData[channel];
}
STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
{
switch (protocol) {
default:
#ifdef USE_RX_V202
case RX_SPI_NRF24_V202_250K:
case RX_SPI_NRF24_V202_1M:
protocolInit = v202Nrf24Init;
protocolDataReceived = v202Nrf24DataReceived;
protocolSetRcDataFromPayload = v202Nrf24SetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_SYMA
case RX_SPI_NRF24_SYMA_X:
case RX_SPI_NRF24_SYMA_X5C:
protocolInit = symaNrf24Init;
protocolDataReceived = symaNrf24DataReceived;
protocolSetRcDataFromPayload = symaNrf24SetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_CX10
case RX_SPI_NRF24_CX10:
case RX_SPI_NRF24_CX10A:
protocolInit = cx10Nrf24Init;
protocolDataReceived = cx10Nrf24DataReceived;
protocolSetRcDataFromPayload = cx10Nrf24SetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_H8_3D
case RX_SPI_NRF24_H8_3D:
protocolInit = h8_3dNrf24Init;
protocolDataReceived = h8_3dNrf24DataReceived;
protocolSetRcDataFromPayload = h8_3dNrf24SetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_KN
case RX_SPI_NRF24_KN:
protocolInit = knNrf24Init;
protocolDataReceived = knNrf24DataReceived;
protocolSetRcDataFromPayload = knNrf24SetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_INAV
case RX_SPI_NRF24_INAV:
protocolInit = inavNrf24Init;
protocolDataReceived = inavNrf24DataReceived;
protocolSetRcDataFromPayload = inavNrf24SetRcDataFromPayload;
break;
#endif
#if defined(USE_RX_FRSKY_SPI)
#if defined(USE_RX_FRSKY_SPI_D)
case RX_SPI_FRSKY_D:
#endif
#if defined(USE_RX_FRSKY_SPI_X)
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
#endif
protocolInit = frSkySpiInit;
protocolDataReceived = frSkySpiDataReceived;
protocolSetRcDataFromPayload = frSkySpiSetRcData;
protocolProcessFrame = frSkySpiProcessFrame;
break;
#endif // USE_RX_FRSKY_SPI
#ifdef USE_RX_FLYSKY
case RX_SPI_A7105_FLYSKY:
case RX_SPI_A7105_FLYSKY_2A:
protocolInit = flySkyInit;
protocolDataReceived = flySkyDataReceived;
protocolSetRcDataFromPayload = flySkySetRcDataFromPayload;
break;
#endif
#ifdef USE_RX_SFHSS_SPI
case RX_SPI_SFHSS:
protocolInit = sfhssSpiInit;
protocolDataReceived = sfhssSpiDataReceived;
protocolSetRcDataFromPayload = sfhssSpiSetRcData;
break;
#endif
#ifdef USE_RX_SPEKTRUM
case RX_SPI_CYRF6936_DSM:
protocolInit = spektrumSpiInit;
protocolDataReceived = spektrumSpiDataReceived;
protocolSetRcDataFromPayload = spektrumSpiSetRcDataFromPayload;
break;
#endif
}
return true;
}
/*
* Returns true if the RX has received new data.
* Called from updateRx in rx.c, updateRx called from taskUpdateRxCheck.
* If taskUpdateRxCheck returns true, then taskUpdateRxMain will shortly be called.
*/
static uint8_t rxSpiFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
{
UNUSED(rxRuntimeConfig);
uint8_t status = RX_FRAME_PENDING;
rx_spi_received_e result = protocolDataReceived(rxSpiPayload);
if (result & RX_SPI_RECEIVED_DATA) {
rxSpiNewPacketAvailable = true;
status = RX_FRAME_COMPLETE;
}
if (result & RX_SPI_ROCESSING_REQUIRED) {
status |= RX_FRAME_PROCESSING_REQUIRED;
}
return status;
}
static bool rxSpiProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
{
UNUSED(rxRuntimeConfig);
if (protocolProcessFrame) {
rx_spi_received_e result = protocolProcessFrame(rxSpiPayload);
if (result & RX_SPI_RECEIVED_DATA) {
rxSpiNewPacketAvailable = true;
}
if (result & RX_SPI_ROCESSING_REQUIRED) {
return false;
}
}
return true;
}
/*
* Set and initialize the RX protocol
*/
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
bool ret = false;
if (!rxSpiDeviceInit(rxSpiConfig)) {
return false;
}
if (rxSpiSetProtocol(rxSpiConfig->rx_spi_protocol)) {
ret = protocolInit(rxSpiConfig, rxRuntimeConfig);
}
rxSpiNewPacketAvailable = false;
rxRuntimeConfig->rxRefreshRate = 20000;
rxRuntimeConfig->rcReadRawFn = rxSpiReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = rxSpiFrameStatus;
rxRuntimeConfig->rcProcessFrameFn = rxSpiProcessFrame;
return ret;
}
#endif
@@ -0,0 +1,91 @@
#include "cc2500_compat.h"
#include "cc2500_settings.h"
#include "cc2500_rx.h"
// betaflight/src/main/rx/rx_spi.h @ 766c90b
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "pg/rx.h"
//#include "rx/rx.h"
//#include "pg/rx_spi.h"
// Used in MSP. Append at end.
typedef enum {
RX_SPI_NRF24_V202_250K = 0,
RX_SPI_NRF24_V202_1M,
RX_SPI_NRF24_SYMA_X,
RX_SPI_NRF24_SYMA_X5C,
RX_SPI_NRF24_CX10,
RX_SPI_NRF24_CX10A,
RX_SPI_NRF24_H8_3D,
RX_SPI_NRF24_INAV,
RX_SPI_FRSKY_D,
RX_SPI_FRSKY_X,
RX_SPI_A7105_FLYSKY,
RX_SPI_A7105_FLYSKY_2A,
RX_SPI_NRF24_KN,
RX_SPI_SFHSS,
RX_SPI_CYRF6936_DSM,
RX_SPI_FRSKY_X_LBT,
RX_SPI_PROTOCOL_COUNT
} rx_spi_protocol_e;
typedef enum {
RX_SPI_RECEIVED_NONE = 0,
RX_SPI_RECEIVED_BIND = (1 << 0),
RX_SPI_RECEIVED_DATA = (1 << 1),
RX_SPI_ROCESSING_REQUIRED = (1 << 2),
} rx_spi_received_e;
// RC channels in AETR order
typedef enum {
RC_SPI_ROLL = 0,
RC_SPI_PITCH,
RC_SPI_THROTTLE,
RC_SPI_YAW,
RC_SPI_AUX1,
RC_SPI_AUX2,
RC_SPI_AUX3,
RC_SPI_AUX4,
RC_SPI_AUX5,
RC_SPI_AUX6,
RC_SPI_AUX7,
RC_SPI_AUX8,
RC_SPI_AUX9,
RC_SPI_AUX10,
RC_SPI_AUX11,
RC_SPI_AUX12,
RC_SPI_AUX13,
RC_SPI_AUX14
} rc_spi_aetr_e;
// RC channels as used by deviation
#define RC_CHANNEL_RATE RC_SPI_AUX1
#define RC_CHANNEL_FLIP RC_SPI_AUX2
#define RC_CHANNEL_PICTURE RC_SPI_AUX3
#define RC_CHANNEL_VIDEO RC_SPI_AUX4
#define RC_CHANNEL_HEADLESS RC_SPI_AUX5
#define RC_CHANNEL_RTH RC_SPI_AUX6 // return to home
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
@@ -0,0 +1,148 @@
#include "cc2500_compat.h"
#include "cc2500_rx_spi_common.h"
// betaflight/src/main/rx/rx_spi_common.c @ afb2bf5
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
//#include "platform.h"
#ifdef USE_RX_SPI
//#include "drivers/io.h"
//#include "drivers/time.h"
//#include "rx/rx_spi_common.h"
//#include "rx/rx_spi.h"
static IO_t ledPin;
static bool ledInversion = false;
static IO_t bindPin;
static bool bindRequested;
static bool lastBindPinStatus;
void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig)
{
if (rxSpiConfig->ledIoTag) {
ledPin = IOGetByTag(rxSpiConfig->ledIoTag);
IOInit(ledPin, OWNER_LED, 0);
IOConfigGPIO(ledPin, IOCFG_OUT_PP);
ledInversion = rxSpiConfig->ledInversion;
rxSpiLedOff();
} else {
ledPin = IO_NONE;
}
if (rxSpiConfig->bindIoTag) {
bindPin = IOGetByTag(rxSpiConfig->bindIoTag);
IOInit(bindPin, OWNER_RX_SPI_BIND, 0);
IOConfigGPIO(bindPin, IOCFG_IPU);
lastBindPinStatus = IORead(bindPin);
} else {
bindPin = IO_NONE;
}
}
void rxSpiLedOn(void)
{
if (ledPin) {
ledInversion ? IOLo(ledPin) : IOHi(ledPin);
}
}
void rxSpiLedOff(void)
{
if (ledPin) {
ledInversion ? IOHi(ledPin) : IOLo(ledPin);
}
}
void rxSpiLedToggle(void)
{
if (ledPin) {
IOToggle(ledPin);
}
}
void rxSpiLedBlink(timeMs_t blinkMs)
{
static timeMs_t ledBlinkMs = 0;
if ((ledBlinkMs + blinkMs) > millis()) {
return;
}
ledBlinkMs = millis();
rxSpiLedToggle();
}
void rxSpiLedBlinkRxLoss(rx_spi_received_e result)
{
static uint16_t rxLossCount = 0;
if (ledPin) {
if (result == RX_SPI_RECEIVED_DATA) {
rxLossCount = 0;
rxSpiLedOn();
} else {
if (rxLossCount < RX_LOSS_COUNT) {
rxLossCount++;
} else {
rxSpiLedBlink(INTERVAL_RX_LOSS_MS);
}
}
}
}
void rxSpiLedBlinkBind(void)
{
rxSpiLedBlink(INTERVAL_RX_BIND_MS);
}
void rxSpiBind(void)
{
bindRequested = true;
}
bool rxSpiCheckBindRequested(bool reset)
{
if (bindPin) {
bool bindPinStatus = IORead(bindPin);
if (lastBindPinStatus && !bindPinStatus) {
bindRequested = true;
}
lastBindPinStatus = bindPinStatus;
}
if (!bindRequested) {
return false;
} else {
if (reset) {
bindRequested = false;
}
return true;
}
}
#endif
@@ -0,0 +1,44 @@
#include "cc2500_compat.h"
#include "cc2500_rx_spi.h"
// betaflight/src/main/rx/rx_spi_common.h @ c88a5a3
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
//#include "rx/rx_spi.h"
#define INTERVAL_RX_LOSS_MS 1000
#define INTERVAL_RX_BIND_MS 250
#define RX_LOSS_COUNT 1000
void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig);
void rxSpiLedOn(void);
void rxSpiLedOff(void);
void rxSpiLedToggle(void);
void rxSpiLedBlink(timeMs_t blinkMs);
void rxSpiLedBlinkRxLoss(rx_spi_received_e result);
void rxSpiLedBlinkBind(void);
void rxSpiBind(void);
bool rxSpiCheckBindRequested(bool reset);
@@ -0,0 +1,209 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* 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.
*/
#include "cc2500_settings.h"
#include "cc2500_rx_spi.h"
#include BOARD_CONFIG
#include "mcu_periph/gpio.h"
#include "generated/airframe.h"
#include "subsystems/settings.h"
#include <string.h>
#define _LED_GPIO(l) l ## _GPIO
#define LED_GPIO(l) _LED_GPIO(l)
#define _LED_GPIO_PIN(l) l ## _GPIO_PIN
#define LED_GPIO_PIN(l) _LED_GPIO_PIN(l)
#define _LED_GPIO_ON(l) l ## _GPIO_ON
#define LED_GPIO_ON(l) _LED_GPIO_ON(l)
#define _LED_GPIO_OFF(l) l ## _GPIO_OFF
#define LED_GPIO_OFF(l) _LED_GPIO_OFF(l)
#define _BUTTON_GPIO(b) b ## _GPIO
#define BUTTON_GPIO(b) _BUTTON_GPIO(b)
#define _BUTTON_PIN(b) b ## _PIN
#define BUTTON_PIN(b) _BUTTON_PIN(b)
#ifndef CC2500_RX_SPI_PROTOCOL
#define CC2500_RX_SPI_PROTOCOL RX_SPI_FRSKY_X_LBT
#endif
#ifndef CC2500_AUTOBIND
#define CC2500_AUTOBIND FALSE
#endif
#ifndef CC2500_TELEMETRY_SENSORS
#define CC2500_TELEMETRY_SENSORS (SENSOR_VOLTAGE | SENSOR_CURRENT | SENSOR_FUEL | SENSOR_ALTITUDE | SENSOR_VARIO)
#endif
static void cc2500_persistent_write(void);
// main/config/config.h:
void bf_writeEEPROM(void) {
// Settings storage handled by paparazzi's persistent settings
cc2500_persistent_write();
settings_StoreSettings(1);
}
// main/pg/rx.h:
static rxConfig_t rxconfig;
const rxConfig_t* rxConfig(void) {
return &rxconfig;
}
// main/pg/rx_spi.h:
static struct gpio_t extiIo;
static struct gpio_t ledIo;
static struct gpio_t bindIo;
static rxSpiConfig_t spiconfig;
const rxSpiConfig_t* rxSpiConfig(void) {
return &spiconfig;
}
// main/pg/rx_spi_cc2500.h:
static rxCc2500SpiConfig_t cc2500spiconfig;
const rxCc2500SpiConfig_t* rxCc2500SpiConfig(void) {
return &cc2500spiconfig;
}
rxCc2500SpiConfig_t* rxCc2500SpiConfigMutable(void) {
return &cc2500spiconfig;
}
// main/telemetry/telemetry.h:
static telemetryConfig_t telemetryconfig;
const telemetryConfig_t* telemetryConfig(void) {
return &telemetryconfig;
}
// main/telemetry/telemetry.h:
bool telemetryIsSensorEnabled(sensor_e sensor) {
return sensor & CC2500_TELEMETRY_SENSORS;
}
// Paparazzi code
struct cc2500_settings_persistent_s cc2500_settings_persistent;
static void cc2500_persistent_write(void) {
cc2500_settings_persistent.bindVars =
cc2500spiconfig.bindTxId[0] |
cc2500spiconfig.bindTxId[1] << 8 |
cc2500spiconfig.bindOffset << 16 |
cc2500spiconfig.rxNum << 24;
for (int i = 0; i < 48; i += 4) {
cc2500_settings_persistent.bindHopData[i / 4] =
cc2500spiconfig.bindHopData[i] |
cc2500spiconfig.bindHopData[i + 1] << 8 |
cc2500spiconfig.bindHopData[i + 2] << 16 |
cc2500spiconfig.bindHopData[i + 3] << 24;
}
cc2500_settings_persistent.bindHopData[12] =
cc2500spiconfig.bindHopData[48] |
cc2500spiconfig.bindHopData[49] << 8 |
0xFF << 24;
}
static void cc2500_persistent_read(void) {
// Check that persistent data is loaded
// highest bindHopData byte is initialized 0 at boot
if (cc2500_settings_persistent.bindHopData[12] >> 24) {
cc2500spiconfig.bindTxId[0] = cc2500_settings_persistent.bindVars & 0xFF;
cc2500spiconfig.bindTxId[1] = (cc2500_settings_persistent.bindVars >> 8) & 0xFF;
cc2500spiconfig.bindOffset = (cc2500_settings_persistent.bindVars >> 16) & 0xFF;
cc2500spiconfig.rxNum = (cc2500_settings_persistent.bindVars >> 24) & 0xFF;
}
for (int i = 0; i < 48; i += 4) {
cc2500spiconfig.bindHopData[i] = cc2500_settings_persistent.bindHopData[i / 4] & 0xFF;
cc2500spiconfig.bindHopData[i + 1] = (cc2500_settings_persistent.bindHopData[i / 4] >> 8) & 0xFF;
cc2500spiconfig.bindHopData[i + 2] = (cc2500_settings_persistent.bindHopData[i / 4] >> 16) & 0xFF;
cc2500spiconfig.bindHopData[i + 3] = (cc2500_settings_persistent.bindHopData[i / 4] >> 24) & 0xFF;
}
cc2500spiconfig.bindHopData[48] = cc2500_settings_persistent.bindHopData[12] & 0xFF;
cc2500spiconfig.bindHopData[49] = (cc2500_settings_persistent.bindHopData[12] >> 8) & 0xFF;
}
void cc2500_settings_init(void) {
// rxConfig
rxconfig.rssi_channel = 0;
rxconfig.midrc = 1500;
rxconfig.max_aux_channel = 0; // TODO
rxconfig.rssi_src_frame_lpf_period = 30;
// rxSpiConfig
spiconfig.rx_spi_protocol = CC2500_RX_SPI_PROTOCOL;
extiIo.port = CC2500_GDO0_GPIO;
extiIo.pin = CC2500_GDO0_PIN;
spiconfig.extiIoTag = &extiIo;
#ifdef CC2500_RX_LED
ledIo.port = LED_GPIO(CC2500_RX_LED);
ledIo.pin = LED_GPIO_PIN(CC2500_RX_LED);
ledIo.hi = LED_GPIO_ON(CC2500_RX_LED);
ledIo.lo = LED_GPIO_OFF(CC2500_RX_LED);
spiconfig.ledIoTag = &ledIo;
#else
(void) ledIo;
spiconfig.ledIoTag = NULL;
#endif
spiconfig.ledInversion = FALSE; // Handled by paparazzi LED_X_GPIO_ON|_OFF
#ifdef CC2500_BIND_BUTTON
bindIo.port = BUTTON_GPIO(CC2500_BIND_BUTTON);
bindIo.pin = BUTTON_PIN(CC2500_BIND_BUTTON);
spiconfig.bindIoTag = &bindIo;
#else
(void) bindIo;
spiconfig.bindIoTag = NULL;
#endif
// rxCc2500SpiConfig
cc2500spiconfig.autoBind = CC2500_AUTOBIND;
cc2500spiconfig.bindTxId[0] = 0;
cc2500spiconfig.bindTxId[1] = 0;
cc2500spiconfig.bindOffset = 0;
memset(cc2500spiconfig.bindHopData, 0, sizeof(cc2500spiconfig.bindHopData));
cc2500spiconfig.rxNum = 0;
cc2500spiconfig.a1Source = FRSKY_SPI_A1_SOURCE_VBAT;
cc2500spiconfig.chipDetectEnabled = TRUE;
settings_init();
cc2500_persistent_read();
// telemetryConfig
telemetryconfig.pidValuesAsTelemetry = FALSE;
telemetryconfig.report_cell_voltage = FALSE;
}
@@ -0,0 +1,192 @@
/*
* Copyright (C) 2019 Tom van Dijk <tomvand@users.noreply.github.com>
*
* This code is based on the betaflight cc2500 and FrskyX implementation.
* https://github.com/betaflight/betaflight
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
#ifndef RADIO_CONTROL_CC2500_SETTINGS_H
#define RADIO_CONTROL_CC2500_SETTINGS_H
#include "cc2500_compat.h"
#include <stdint.h>
/* Paparazzi settings */
void cc2500_settings_init(void);
struct cc2500_settings_persistent_s {
uint32_t bindVars;
uint32_t bindHopData[13];
};
extern struct cc2500_settings_persistent_s cc2500_settings_persistent;
/* betaflight settings API */
// main/config/config.h:
void bf_writeEEPROM(void);
#define writeEEPROM() bf_writeEEPROM()
// main/pg/rx.h:
#define FRAME_ERR_RESAMPLE_US 100000
#define GET_FRAME_ERR_LPF_FREQUENCY(period) (1 / (period / 10.0f))
typedef struct rxConfig_s {
// uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
// uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
// uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
// ioTag_t spektrum_bind_pin_override_ioTag;
// ioTag_t spektrum_bind_plug_ioTag;
// uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
// uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
uint8_t rssi_channel;
// uint8_t rssi_scale;
// uint8_t rssi_invert;
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
// uint16_t mincheck; // minimum rc end
// uint16_t maxcheck; // maximum rc end
// uint8_t rcInterpolation;
// uint8_t rcInterpolationChannels;
// uint8_t rcInterpolationInterval;
// uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
// uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
//
// uint16_t rx_min_usec;
// uint16_t rx_max_usec;
uint8_t max_aux_channel;
// uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
// int8_t rssi_offset; // offset applied to the RSSI value before it is returned
// uint8_t rc_smoothing_type; // Determines the smoothing algorithm to use: INTERPOLATION or FILTER
// uint8_t rc_smoothing_input_cutoff; // Filter cutoff frequency for the input filter (0 = auto)
// uint8_t rc_smoothing_derivative_cutoff; // Filter cutoff frequency for the setpoint weight derivative filter (0 = auto)
// uint8_t rc_smoothing_debug_axis; // Axis to log as debug values when debug_mode = RC_SMOOTHING
// uint8_t rc_smoothing_input_type; // Input filter type (0 = PT1, 1 = BIQUAD)
// uint8_t rc_smoothing_derivative_type; // Derivative filter type (0 = OFF, 1 = PT1, 2 = BIQUAD)
// uint8_t rc_smoothing_auto_factor; // Used to adjust the "smoothness" determined by the auto cutoff calculations
uint8_t rssi_src_frame_lpf_period; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s)
//
// uint8_t srxl2_unit_id; // Spektrum SRXL2 RX unit id
// uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate
// uint8_t sbus_baud_fast; // Select SBus fast baud rate
} rxConfig_t;
const rxConfig_t* rxConfig(void);
// main/pg/rx_spi.h:
typedef struct rxSpiConfig_s {
// RX protocol
uint8_t rx_spi_protocol; // type of SPI RX protocol
// // nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
// uint32_t rx_spi_id;
// uint8_t rx_spi_rf_channel_count;
//
// // SPI Bus
// ioTag_t csnTag;
// uint8_t spibus;
//
ioTag_t bindIoTag;
ioTag_t ledIoTag;
uint8_t ledInversion;
ioTag_t extiIoTag;
} rxSpiConfig_t;
const rxSpiConfig_t* rxSpiConfig(void);
// main/pg/rx_spi_cc2500.h:
typedef enum {
FRSKY_SPI_A1_SOURCE_VBAT = 0,
FRSKY_SPI_A1_SOURCE_EXTADC,
FRSKY_SPI_A1_SOURCE_CONST
} frSkySpiA1Source_e;
typedef struct rxCc2500SpiConfig_s {
uint8_t autoBind;
uint8_t bindTxId[2];
int8_t bindOffset;
uint8_t bindHopData[50];
uint8_t rxNum;
uint8_t a1Source;
uint8_t chipDetectEnabled;
// ioTag_t txEnIoTag;
// ioTag_t lnaEnIoTag;
// ioTag_t antSelIoTag;
} rxCc2500SpiConfig_t;
const rxCc2500SpiConfig_t* rxCc2500SpiConfig(void);
rxCc2500SpiConfig_t* rxCc2500SpiConfigMutable(void);
// main/telemetry/telemetry.h:
typedef struct telemetryConfig_s {
// int16_t gpsNoFixLatitude;
// int16_t gpsNoFixLongitude;
// uint8_t telemetry_inverted;
// uint8_t halfDuplex;
// frskyGpsCoordFormat_e frsky_coordinate_format;
// frskyUnit_e frsky_unit;
// uint8_t frsky_vfas_precision;
// uint8_t hottAlarmSoundInterval;
uint8_t pidValuesAsTelemetry;
uint8_t report_cell_voltage;
// uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
// uint16_t mavlink_mah_as_heading_divisor;
// uint32_t disabledSensors; // bit flags
} telemetryConfig_t;
const telemetryConfig_t* telemetryConfig(void);
typedef enum {
SENSOR_VOLTAGE = 1 << 0,
SENSOR_CURRENT = 1 << 1,
SENSOR_FUEL = 1 << 2,
SENSOR_MODE = 1 << 3,
SENSOR_ACC_X = 1 << 4,
SENSOR_ACC_Y = 1 << 5,
SENSOR_ACC_Z = 1 << 6,
SENSOR_PITCH = 1 << 7,
SENSOR_ROLL = 1 << 8,
SENSOR_HEADING = 1 << 9,
SENSOR_ALTITUDE = 1 << 10,
SENSOR_VARIO = 1 << 11,
SENSOR_LAT_LONG = 1 << 12,
SENSOR_GROUND_SPEED = 1 << 13,
SENSOR_DISTANCE = 1 << 14,
ESC_SENSOR_CURRENT = 1 << 15,
ESC_SENSOR_VOLTAGE = 1 << 16,
ESC_SENSOR_RPM = 1 << 17,
ESC_SENSOR_TEMPERATURE = 1 << 18,
ESC_SENSOR_ALL = ESC_SENSOR_CURRENT \
| ESC_SENSOR_VOLTAGE \
| ESC_SENSOR_RPM \
| ESC_SENSOR_TEMPERATURE,
SENSOR_TEMPERATURE = 1 << 19,
SENSOR_ALL = (1 << 20) - 1,
} sensor_e;
#define SENSOR_NONE 0
bool telemetryIsSensorEnabled(sensor_e sensor);
#endif // RADIO_CONTROL_CC2500_SETTINGS_H
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,97 @@
#include "cc2500_compat.h"
/* SmartPort downlink hook
* Called from smartport telemetry loop.
* Write telemetry stream to 'data'.
* Return 'true' if data is written.
*/
typedef bool smartPortDownlinkFn(uint32_t *data);
extern smartPortDownlinkFn *smartPortDownlink;
/* SmartPort uplink hook
* Called from processSmartPortTelemetry
*/
struct smartPortPayload_s;
typedef void smartPortUplinkFn(struct smartPortPayload_s *payload);
extern smartPortUplinkFn *smartPortUplink;
// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT!
// betaflight/src/main/telemetry/smartport.h @ 41492e1
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* smartport.h
*
* Created on: 25 October 2014
* Author: Frank26080115
*/
#pragma once
#include <stdbool.h>
#include <stdint.h>
//#define SMARTPORT_MSP_TX_BUF_SIZE 256
//#define SMARTPORT_MSP_RX_BUF_SIZE 64
enum
{
FSSP_START_STOP = 0x7E,
FSSP_DLE = 0x7D,
FSSP_DLE_XOR = 0x20,
FSSP_DATA_FRAME = 0x10,
FSSP_MSPC_FRAME_SMARTPORT = 0x30, // MSP client frame
FSSP_MSPC_FRAME_FPORT = 0x31, // MSP client frame
FSSP_MSPS_FRAME = 0x32, // MSP server frame
// ID of sensor. Must be something that is polled by FrSky RX
FSSP_SENSOR_ID1 = 0x1B,
FSSP_SENSOR_ID2 = 0x0D,
FSSP_SENSOR_ID3 = 0x34,
FSSP_SENSOR_ID4 = 0x67
// there are 32 ID's polled by smartport master
// remaining 3 bits are crc (according to comments in openTx code)
};
typedef struct smartPortPayload_s {
uint8_t frameId;
uint16_t valueId;
uint32_t data;
} __attribute__((packed)) smartPortPayload_t;
typedef void smartPortWriteFrameFn(const smartPortPayload_t *payload);
typedef bool smartPortCheckQueueEmptyFn(void);
//bool initSmartPortTelemetry(void);
//void checkSmartPortTelemetryState(void);
bool initSmartPortTelemetryExternal(smartPortWriteFrameFn *smartPortWriteFrameExternal);
//void handleSmartPortTelemetry(void);
void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *hasRequest, const uint32_t *requestTimeout);
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool withChecksum);
//struct serialPort_s;
//void smartPortWriteFrameSerial(const smartPortPayload_t *payload, struct serialPort_s *port, uint16_t checksum);
//void smartPortSendByte(uint8_t c, uint16_t *checksum, struct serialPort_s *port);
//bool smartPortPayloadContainsMSP(const smartPortPayload_t *payload);
+73
View File
@@ -0,0 +1,73 @@
-- SmartPort to serial bridge
-- TELEMETRY SCRIPT
--
-- Requires opentx compilation flags -DLUA=YES -DUSB_SERIAL=YES -DCLI=NO
--
-- On TX, set hardware USB mode to serial
-- Add this script as telemetry script to your model
local downlink_str = ""
local uplink_str = ""
local function init_func()
end
local function downlink_bg()
local sensorId, frameId, dataId, value = sportTelemetryPop()
while frameId do
if dataId == 0x5015 then
local value0 = math.floor(value / 16777216) % 256
local value1 = math.floor(value / 65536) % 256
local value2 = math.floor(value / 256) % 256
local value3 = value % 256
serialWrite(string.char(value0) .. string.char(value1) .. string.char(value2) .. string.char(value3))
downlink_str = string.format("0x %X %X %X %X", value0, value1, value2, value3)
end
sensorId, frameId, dataId, value = sportTelemetryPop()
end
end
local uplink_buf = ""
local function uplink_bg()
if string.len(uplink_buf) < 4 then
-- Grab new/more data from the serial line
local new_bytes = serialRead(4 - string.len(uplink_buf))
uplink_buf = uplink_buf .. new_bytes
end
if string.len(uplink_buf) > 0 then
-- Data ready to transmit
local sensorId = 0x0D -- see smartport.c::smartPortDataReceive
local frameId = string.len(uplink_buf)
local dataId = 0x5016
local value = 0
local byte = 16777216
for i=1,string.len(uplink_buf) do
value = value + byte * string.byte(uplink_buf, i)
byte = byte / 256
end
-- DEBUG
-- frameId = 2
-- value = 0xABCDEF12
-- DEBUG
local ret = sportTelemetryPush(sensorId, frameId, dataId, value)
if ret then
-- Uplink successful, signal that new data can be read
uplink_buf = ""
uplink_str = string.format("0x%X (%s)", value, frameId)
end
end
end
local function bg_func()
downlink_bg()
uplink_bg()
end
local function run_func(event)
lcd.clear()
lcd.drawText(1, 1, "sp2ser is running...")
lcd.drawText(1, 11, "Downlink: '" .. downlink_str .. "'")
lcd.drawText(1, 21, "Uplink: '" .. uplink_str .. "'")
end
return {run = run_func, background = bg_func, init = init_func}