[board] add support of the MatekF405 board

includes baro bmp280 and updated max7456 osb

Squashed commit of the following:

commit 647ec61a9a16966b523bbf5f535ce85679785c9a
Author: Gautier Hattenberger <gautier.hattenberger@enac.fr>
Date:   Wed Oct 14 18:33:02 2020 +0200

    [conf] matek board module only configure internal sensors

    it makes it easier to reuse by other people

commit 9bfa96685d
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 17:41:32 2020 +0300

    Easyglider with Matek F405 Wing autopilot airframes

    Added coordinated turning using both the ailerons and the rudder in Auto2

commit e736781ac3
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 17:40:05 2020 +0300

    Easyglider with Matek F405 Wing autopilot airframes.

    I added the combi switch for coordinated turns using both the alilerons and the rudder in Auto2.

commit 8be348a1d8
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 17:39:02 2020 +0300

    Easyglider with Matek F405 Wing autopilot

    I added the combi switch for coordinated turns using both the alilerons and the rudder in Auto2.

commit c0f7339686
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 16:19:35 2020 +0300

    Easyglider and Matek wing autopilot module autoload file

    I just added some comments.

commit c4645705ad
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 16:12:44 2020 +0300

    Easyglider with Matek wing autopilot and module autoload/

    This airframe file needs the paparazzi/conf/module/board_matek_wing.xml file in order to compile.

commit 2c273589d3
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 16:04:50 2020 +0300

    board module for auto loading the required modules

    I don't usually change those airframe modules so i put them all in the board module file.

commit 58e1e551d1
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 13:34:18 2020 +0300

    Removed the Baro definitions and cleaned up the file.

commit a1a47ec150
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 13:30:02 2020 +0300

    Corrected the autopilot type and link to the manufacturer.

commit 870f2d2e94
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 13:26:41 2020 +0300

    Removed the .xml file type from modules and changed the spoken aircraft name.

commit 700141cc9c
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 08:05:31 2020 +0300

    Added support for the Matek F405 Wing autopilot OSD.

    Removed all warning and pragma messages and used PRINT_CONFIG_MSG() instead.
    Added support for rotorcrafts which i don't like....
    Matek osd will work now, TEXT artificial horizon is added, additional string format capabilities are given in the osd_put_s() and osd_sprintf() functions , able to inject special osd character code in to a string to be sent to the osd display
    and the code now checks the osd chip's busy flag instead of waiting and hoping that the OSD is not busy.

commit fe17c0250c
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Wed Oct 14 07:30:11 2020 +0300

    Update osd_max7456.xml

    I removed the PAL or NTSC selection because i think this should be done in the airframe file.

commit a1966511f9
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 22:38:21 2020 +0300

    Matek F405 Wing OSD support

    Added support for rotorcrafts which i don't like....
    Matek osd will work now, TEXT artificial horizon is added, additional string format capabilities are given in the osd_put_s() and osd_sprintf() functions , able to inject special osd character code in to a string to be sent to the osd display
    and the code now checks the osd chip's busy flag instead of waiting and hoping that the OSD is not busy.

commit 4edaecc3bf
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 21:34:38 2020 +0300

    Matek OSD support

    I changed the HOME waypoint altitude to ground alt in order to avoid a compiler error about not finding  waypoints[WP_HOME].a
    Matek osd will work now, TEXT artificial horizon is added, additional string format capabilities are given in the osd_put_s() and osd_sprintf() functions , able to inject special osd character code in to a string to be sent to the osd display
    and the code now checks the osd chip's busy flag instead of waiting and hoping that the OSD is not busy.

commit 201d5e7793
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 19:51:15 2020 +0300

    Delete Easystar_matek_f405_wing.xml

commit a6730fb148
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 19:49:50 2020 +0300

    Easyglider airframe file corrected.

    It had the parachute radio channel in it which doesn't exist but strangely it was compiling fine here until i deleted the aircraft and created a new one.

commit a430091754
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 18:26:31 2020 +0300

    Baro BMP280 files

    I can only test the BMP280 in I2C mode so SPI must wait...

commit 2bc25212ac
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 18:22:47 2020 +0300

    Barometer BMP280 files

    This time only double precision is available.

commit 03dc09de77
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 18:18:16 2020 +0300

    Matek F405 Wing board header file

    The Matek autopilot can measure up to 104A so logically 104 /4096 step of the ADC should give 25,3 ma for every adc count.
    Some measurements are needed.

commit c77c2365da
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 18:04:49 2020 +0300

    Barometer BMP280 module XML file.

commit 2e3721bbad
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 16:21:06 2020 +0300

    Improved OSD and Matek type OSD support.

    Matek osd will work now, TEXT artificial horizon is added, additional string format capabilities are given in the osd_put_s() and osd_sprintf() functions , able to inject special osd character code in to a string to be sent to the osd display
    and the code now checks the osd chip's busy flag instead of waiting and hoping that the OSD is not busy.

commit f67172d1a6
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 15:48:54 2020 +0300

    Radio file for OPENTX radios and 8 channels PPM signal

commit 294341357e
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 15:45:37 2020 +0300

    Telemetry file for use with the orangerx loaded with the OPENLRSNG firmware

    Telemetry file for use with the orangerx 433 Mhz receiver or any other OPENLRSNG capable receiver.
    The OPENLRSNG receivers have a transparent serial datalink built in to the radio control signal thus eliminating the need for a separate modem.

commit e8905c8158
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 15:38:53 2020 +0300

    Easystar glider with the MATEK F405 WING

    Airframe file of the Easystar powered glider with the Matek F405 Wing autopilot.

commit de3f5f54b3
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 12:33:09 2020 +0300

    improved osd

    Matek osd will work now, TEXT artificial horizon, additional string format capabilities, able to inject special osd character code in to a string to be sent to the osd display
    and the code now checks the osd chip's busy flag instead of waiting.

commit 78ae7cccc3
Author: hendrixgr <hendrixgr@gmail.com>
Date:   Tue Oct 13 12:27:56 2020 +0300

    matek f405 wing autopilot makefile
This commit is contained in:
hendrixgr
2020-10-14 21:26:53 +02:00
committed by Gautier Hattenberger
parent 972b17a37f
commit 8b56049d21
15 changed files with 2563 additions and 216 deletions
@@ -0,0 +1,336 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Easyglider_Matek">
<description>
Easyglider from Multiplex
BOARD = Matek f405 Wing
IMU = MPU6000
BARO = BMP280
Radio modem: OPENLRSNG
Radio control: OPENLRSNG
GPS: Ublox
On Board OSD
On board current sensor
</description>
<firmware name="fixedwing">
<target name="ap" board="matek_f405_wing_v1"/>
<target name="sim" board="pc"/>
<define name="AGR_CLIMB"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="STRONG_WIND"/>
<define name="USE_ADC_1"/>
<define name="USE_ADC_2"/>
<define name="USE_ADC_3"/>
<define name="USE_ADC_4"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<define name="USE_AHRS_GPS_ACCELERATIONS"/>
<define name="MAGNETOMETER_AVAILABLE" value="0" />
<define name="BAROMETER_AVAILABLE" value="0" />
<!-- load standard internal sensors, then custom modules -->
<module name="board_matek_wing">
<define name="BMP280_SYNC_SEND"/>
</module>
<module name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART6 "/>
</module>
<module name="gps" type="ublox" >
<configure name="GPS_BAUD" value="B38400"/>
<configure name="GPS_PORT" value="UART1"/>
<configure name="GPS_LED" value="2"/>
</module>
<module name="control" />
<module name="radio_control" type="ppm">
<define name="RADIO_CONTROL_PPM_PIN" value="UART2_RX"/>
</module>
<module name="navigation"/>
<module name="ahrs" type="float_dcm"/>
<module name="ins" type="alt_float">
<configure name="USE_MAGNETOMETER" value="0"/>
<define name="AHRS_USE_GPS_HEADING" value="1"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN"/>
</module>
<module name="nav_line"/>
<module name="gps_ubx_ucenter"/>
</firmware>
<firmware name="setup">
<target name="tunnel" board="matek_f405_wing_v1" />
<target name="usb_tunnel" board="matek_f405_wing_v1">
<configure name="TUNNEL_PORT" value="UART3"/>
</target>
</firmware>
<servos>
<servo name="MOTOR" no="0" min="1100" neutral="1100" max="2000"/>
<servo name="AILERON" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="CAM_PAN" no="5" min="943" neutral="1520" max="2056"/>
<servo name="CAM_TILT" no="6" min="996" neutral="1221" max="2004"/>
<servo name="PARACHUTE" no="7" min="950" neutral="950" max="2050"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="YAW" failsafe_value="2000"/>
<axis name="CAM_PAN" failsafe_value="0"/>
<axis name="CAM_TILT" failsafe_value="0"/>
<axis name="PARACHUTE" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="YAW" value="@YAW"/>
</rc_commands>
<section name="MIXER">
<define name="AILERON_DIFF" value="0.66"/>
<define name="COMBI_SWITCH" value="0.3"/>
</section>
<command_laws>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILERON" value="@ROLL"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>
<set servo="CAM_PAN" value="@CAM_PAN"/>
<set servo="CAM_TILT" value="@CAM_TILT"/>
<set servo="PARACHUTE" value="@PARACHUTE"/>
</command_laws>
<!-- EMPTY "auto_rc_commands" block means NO RC RUDDER CONTROL IN AUTO2 AND AUTO1 -->
<auto_rc_commands>
<!--
<set command="YAW" value="@YAW"/>
-->
</auto_rc_commands>
<ap_only_commands>
<copy command="CAM_PAN"/>
<copy command="CAM_TILT"/>
</ap_only_commands>
<!--
Normalized Local magnetic field obtained from http://www.ngdc.noaa.gov/geomag-web/#igrfwmm
Magnetic field intensity (North-East-vertical) / total field strength
H_x = INTENSITY_x / Total Magnetic Field
Total Magnetic Field = (intensityEAST^2+intensityNORTH^2+intensityVERTICAL^2)
Calculated for LAGONISI ATTIKI 21 AUGUST 2020
-->
<section name="AHRS" prefix="AHRS_" >
<define name="MAG_DECLINATION" value="5.3" />
<define name="H_X" value="(25242.1/47035.5)" />
<define name="H_Y" value="(2224.0/47035.5)" />
<define name="H_Z" value="(39626.2/47035.5) " />
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 14.375 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
<define name="GYRO_P_SENS" value="4.947" integer="16"/>
<define name="GYRO_Q_SENS" value="4.947" integer="16"/>
<define name="GYRO_R_SENS" value="4.947" integer="16"/>
<define name="GYRO_P_Q" value="0."/>
<define name="GYRO_P_R" value="0"/>
<define name="GYRO_Q_P" value="0."/>
<define name="GYRO_Q_R" value="0."/>
<define name="GYRO_R_P" value="0."/>
<define name="GYRO_R_Q" value="0."/>
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<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"/> <!-- YAW -->
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="RadOfDeg(0)" unit="radians"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="RadOfDeg(0)" unit="radians"/>
</section>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="50" unit="deg"/>
<define name="MAX_PITCH" value="40" unit="deg"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- OUTER LOOP PARAMETERS -->
<!-- The below definition affect the throttle percentage shown on the GCS. -->
<define name="POWER_CTL_BAT_NOMINAL" value="12.6" unit="volt"/>
<!-- outer loop ALTITUDE proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.07" unit="(m/s)/m"/>
<!-- outer loop ALTITUDE LIMIT (saturation) -->
<define name="ALTITUDE_MAX_CLIMB" value="3" unit="m/s"/>
<!-- outer loop AIRSPEED proportional gain -->
<define name="AIRSPEED_PGAIN" value="0.2"/>
<!-- INNER LOOP PARAMETERS -->
<!-- The below definitions are used almost always -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.50" unit="%"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.40" unit="%"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.60" unit="%"/>
<define name="THROTTLE_SLEW_LIMITER" value="0.6" unit="s"/>
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(25)"/>
<define name="AUTO_PITCH_MIN_PITCH" value="RadOfDeg(-20)"/>
<!-- Climb loop (throttle) -->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_PITCH" value="0.0" unit="rad"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.008" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.0"/>
<define name="AUTO_THROTTLE_DGAIN" value="0.001"/>
<!-- Climb loop (pitch) -->
<!-- magnitude of elevator movement on altitude change -->
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.15" unit="rad/(m/s)"/>
<define name="AUTO_PITCH_PGAIN" value="0.04"/>
<define name="AUTO_PITCH_IGAIN" value="0.01"/>
<define name="AUTO_PITCH_DGAIN" value="0.0"/>
<!-- Loiter and Dash trimming -->
<define name="AUTO_THROTTLE_LOITER_TRIM" value="0" unit="pprz_t"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="0" unit="pprz_t"/>
<define name="PITCH_LOITER_TRIM" value="0" unit="pprz_t"/>
<define name="PITCH_DASH_TRIM" value="0" unit="pprz_t"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.8"/>
<define name="COURSE_DGAIN" value="0.8"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="1."/>
<define name="PITCH_MAX_SETPOINT" value="20" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-20" unit="deg"/>
<define name="PITCH_PGAIN" value="8000."/>
<define name="ROLL_MAX_SETPOINT" value="45" unit="deg"/>
<define name="ROLL_SLEW" value="0.1"/>
<define name="ROLL_ATTITUDE_GAIN" value="8000"/>
<define name="ROLL_RATE_GAIN" value="500."/>
<define name="PITCH_OF_ROLL" value="RadOfDeg(1.0)"/>
<define name="ELEVATOR_OF_ROLL" value="1250"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<define name="PITCH_DGAIN" value="6."/>
<define name="PITCH_IGAIN" value="100."/>
</section>
<section name="BAT">
<!-- FOR USE WITH A CURRENT SENSOR -->
<define name="CATASTROPHIC_BAT_LEVEL" value="7.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="8.5" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/>
</section>
<section name="MISC">
<define name="CLIMB_AIRSPEED" value="15." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="14." unit="m/s"/>
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>
<define name="STALL_AIRSPEED" value="10." unit="m/s"/>
<define name="AIRSPEED_SETPOINT_SLEW" value="1" unit="s"/>
<define name="NOMINAL_AIRSPEED" value="16" unit="m/s"/>
<define name="MINIMUM_AIRSPEED" value="14." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="26." unit="m/s"/>
<define name="CARROT" value="3." unit="s"/>
<define name="GLIDE_RATIO" value="7."/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="XBEE_INIT" value="\"ATPL2\rATRN1\rATTT80\r\""/>
<define name="NO_XBEE_API_INIT" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="60."/>
<!-- MIN_CIRCLE_RADIUS used and needed for spiral navigation function and panic autolanding turns-->
<define name="MIN_CIRCLE_RADIUS" value="40."/>
<!--UNLOCKED_HOME_MODE if set to TRUE means that HOME mode does not get stuck.
If not set before when you would enter home mode you had to flip a bit via the GCS to get out. -->
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
<!-- RC_LOST_MODE means that if your RC Transmitter signal is not received anymore in the autopilot, e.g. you switch it off
or fly a long range mission you define the wanted mode behaviour here.
If you do not define it, it defaults to flying to the flightplan HOME -->
<define name="RC_LOST_MODE" value="AP_MODE_AUTO2"/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="40"/> <!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
<define name="BLEND_END" value="10"/> <!-- Altitude Error to Blend Aggressive to Regular Climb Modes NOT ZERO!!-->
<define name="CLIMB_THROTTLE" value="1.0"/> <!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="RadOfDeg(20)"/> <!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/> <!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="RadOfDeg(-20)"/> <!-- Pitch for Aggressive Decent -->
<define name="CLIMB_NAV_RATIO" value="0.8"/> <!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
<define name="DESCENT_NAV_RATIO" value="1.0"/>
</section>
<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
<define name="NAV_GROUND_SPEED_PGAIN" value="0.015"/>
<define name="NAV_FOLLOW_PGAIN" value="-0.05"/>
</section>
<section name="GLS_APPROACH" prefix="APP_">
<define name="ANGLE" value="5"/>
<define name="INTERCEPT_AF_TOD" value="10"/>
<define name="TARGET_SPEED" value="13"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="1" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.8" unit="%"/>
<define name="DEFAULT_ROLL" value="10" unit="deg"/>
<define name="DEFAULT_PITCH" value="10" unit="deg"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
</section>
<section name="DATALINK" prefix="DATALINK_">
<define name="DEVICE_TYPE" value="PPRZ"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<section name="GCS">
<define name="AC_ICON" value="flyingwing"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="100"/>
<define name="ALT_SHIFT_PLUS" value="10"/>
<define name="ALT_SHIFT_MINUS" value="-10"/>
<define name="SPEECH_NAME" value="Easyglider"/>
</section>
<section name="SIMU">
<define name="WEIGHT" value ="1."/>
<define name="YAW_RESPONSE_FACTOR" value =".9"/>
<define name="PITCH_RESPONSE_FACTOR" value ="1.5"/>
<define name="ROLL_RESPONSE_FACTOR" value ="20."/>
</section>
</airframe>
@@ -0,0 +1,349 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="Easyglider Matek">
<description>
Easyglider from Multiplex
BOARD = Matek f405 Wing
IMU = MPU6000
BARO = BMP280
Radio modem: OPENLRSNG
Radio control: OPENLRSNG
GPS: Ublox
On Board OSD
On board current sensor
</description>
<firmware name="fixedwing">
<target name="ap" board="matek_f405_wing_v1"/>
<target name="sim" board="pc"/>
<define name="AGR_CLIMB"/>
<define name="WIND_INFO"/>
<define name="WIND_INFO_RET"/>
<define name="STRONG_WIND"/>
<define name="USE_ADC_1"/>
<define name="USE_ADC_2"/>
<define name="USE_ADC_3"/>
<define name="USE_ADC_4"/>
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP"/>
<define name="USE_AHRS_GPS_ACCELERATIONS"/>
<define name="MAGNETOMETER_AVAILABLE" value="0" />
<define name="BAROMETER_AVAILABLE" value="0" />
<module name="telemetry" type="transparent">
<configure name="MODEM_BAUD" value="B57600"/>
<configure name="MODEM_PORT" value="UART6 "/>
</module>
<module name="gps" type="ublox" >
<configure name="GPS_BAUD" value="B38400"/>
<configure name="GPS_PORT" value="UART1"/>
<configure name="GPS_LED" value="2"/>
</module>
<module name="control" />
<module name="radio_control" type="ppm">
<define name="RADIO_CONTROL_PPM_PIN" value="UART2_RX"/>
</module>
<module name="navigation"/>
<module name="imu" type="mpu6000" />
<module name="ahrs" type="float_dcm"/>
<module name="ins" type="alt_float">
<configure name="USE_MAGNETOMETER" value="0"/>
<define name="AHRS_USE_GPS_HEADING" value="1"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN"/>
</module>
<module name="spi" type="master"/>
<module name="nav_line"/>
<module name="gps_ubx_ucenter"/>
<module name="baro_bmp280_i2c">
<define name="BMP280_SYNC_SEND"/>
<configure name="BMP280_I2C_DEV" value="i2c1" />
<configure name="BMP280_SLAVE_ADDR" value="BMP280_I2C_ADDR" />
</module>
<module name="osd_max7456">
<configure name="MAX7456_SPI_DEV" value="spi2" />
<configure name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1" />
<define name="USE_MATEK_TYPE_OSD_CHIP" value="1" />
<define name="USE_PAL_FOR_OSD_VIDEO" value="1" />
<define name="OSD_USE_BARO_ALTITUDE" value="0" />
<define name="BARO_ALTITUDE_VAR" value="baro_alt" /> <!-- if non defined the default var is ''baro_alt'' -->
<define name="OSD_USE_MAG_COMPASS" value="0" />
</module>
</firmware>
<firmware name="setup">
<target name="tunnel" board="matek_f405_wing_v1" />
<target name="usb_tunnel" board="matek_f405_wing_v1">
<configure name="TUNNEL_PORT" value="UART3"/>
</target>
</firmware>
<servos>
<servo name="MOTOR" no="0" min="1100" neutral="1100" max="2000"/>
<servo name="AILERON" no="2" min="2000" neutral="1500" max="1000"/>
<servo name="ELEVATOR" no="3" min="2000" neutral="1500" max="1000"/>
<servo name="RUDDER" no="4" min="1000" neutral="1500" max="2000"/>
<servo name="CAM_PAN" no="5" min="943" neutral="1520" max="2056"/>
<servo name="CAM_TILT" no="6" min="996" neutral="1221" max="2004"/>
<servo name="PARACHUTE" no="7" min="950" neutral="950" max="2050"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="YAW" failsafe_value="2000"/>
<axis name="CAM_PAN" failsafe_value="0"/>
<axis name="CAM_TILT" failsafe_value="0"/>
<axis name="PARACHUTE" failsafe_value="0"/>
</commands>
<rc_commands>
<set command="ROLL" value="@ROLL"/>
<set command="PITCH" value="@PITCH"/>
<set command="THROTTLE" value="@THROTTLE"/>
<set command="YAW" value="@YAW"/>
<!-- <set command="PARACHUTE" value="@PARACHUTE"/> -->
</rc_commands>
<section name="MIXER">
<define name="AILERON_DIFF" value="0.66"/>
<define name="COMBI_SWITCH" value="0.3"/>
</section>
<command_laws>
<set servo="MOTOR" value="@THROTTLE"/>
<set servo="AILERON" value="@ROLL"/>
<set servo="ELEVATOR" value="@PITCH"/>
<set servo="RUDDER" value="@YAW + @ROLL*COMBI_SWITCH"/>
<set servo="CAM_PAN" value="@CAM_PAN"/>
<set servo="CAM_TILT" value="@CAM_TILT"/>
<set servo="PARACHUTE" value="@PARACHUTE"/>
</command_laws>
<!-- EMPTY "auto_rc_commands" block means NO RC RUDDER CONTROL IN AUTO2 AND AUTO1 -->
<auto_rc_commands>
<!--
<set command="YAW" value="@YAW"/>
-->
</auto_rc_commands>
<ap_only_commands>
<copy command="CAM_PAN"/>
<copy command="CAM_TILT"/>
</ap_only_commands>
<!--
Normalized Local magnetic field obtained from http://www.ngdc.noaa.gov/geomag-web/#igrfwmm
Magnetic field intensity (North-East-vertical) / total field strength
H_x = INTENSITY_x / Total Magnetic Field
Total Magnetic Field = (intensityEAST^2+intensityNORTH^2+intensityVERTICAL^2)
Calculated for LAGONISI ATTIKI 21 AUGUST 2020
-->
<section name="AHRS" prefix="AHRS_" >
<define name="MAG_DECLINATION" value="5.3" />
<define name="H_X" value="(25242.1/47035.5)" />
<define name="H_Y" value="(2224.0/47035.5)" />
<define name="H_Z" value="(39626.2/47035.5) " />
</section>
<section name="IMU" prefix="IMU_">
<!-- Calibration Neutral -->
<define name="GYRO_P_NEUTRAL" value="0"/>
<define name="GYRO_Q_NEUTRAL" value="0"/>
<define name="GYRO_R_NEUTRAL" value="0"/>
<!-- SENS = 14.375 LSB/(deg/sec) * 57.6 deg/rad = 828 LSB/rad/sec / 12bit FRAC: 4096 / 828 -->
<define name="GYRO_P_SENS" value="4.947" integer="16"/>
<define name="GYRO_Q_SENS" value="4.947" integer="16"/>
<define name="GYRO_R_SENS" value="4.947" integer="16"/>
<define name="GYRO_P_Q" value="0."/>
<define name="GYRO_P_R" value="0"/>
<define name="GYRO_Q_P" value="0."/>
<define name="GYRO_Q_R" value="0."/>
<define name="GYRO_R_P" value="0."/>
<define name="GYRO_R_Q" value="0."/>
<define name="GYRO_P_SIGN" value="1"/>
<define name="GYRO_Q_SIGN" value="-1"/>
<define name="GYRO_R_SIGN" value="-1"/>
<define name="ACCEL_X_SIGN" value="1"/>
<define name="ACCEL_Y_SIGN" value="-1"/>
<define name="ACCEL_Z_SIGN" value="-1"/>
<define name="MAG_X_SIGN" value="1"/>
<define name="MAG_Y_SIGN" value="1"/>
<define name="MAG_Z_SIGN" value="1"/>
<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"/> <!-- YAW -->
</section>
<section name="INS" prefix="INS_">
<define name="ROLL_NEUTRAL_DEFAULT" value="RadOfDeg(0)" unit="radians"/>
<define name="PITCH_NEUTRAL_DEFAULT" value="RadOfDeg(0)" unit="radians"/>
</section>
<section name="AUTO1" prefix="AUTO1_">
<define name="MAX_ROLL" value="50" unit="deg"/>
<define name="MAX_PITCH" value="40" unit="deg"/>
</section>
<section name="VERTICAL CONTROL" prefix="V_CTL_">
<!-- OUTER LOOP PARAMETERS -->
<!-- The below definition affect the throttle percentage shown on the GCS. -->
<define name="POWER_CTL_BAT_NOMINAL" value="12.6" unit="volt"/>
<!-- outer loop ALTITUDE proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.07" unit="(m/s)/m"/>
<!-- outer loop ALTITUDE LIMIT (saturation) -->
<define name="ALTITUDE_MAX_CLIMB" value="3" unit="m/s"/>
<!-- outer loop AIRSPEED proportional gain -->
<define name="AIRSPEED_PGAIN" value="0.2"/>
<!-- INNER LOOP PARAMETERS -->
<!-- The below definitions are used almost always -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.50" unit="%"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.40" unit="%"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.60" unit="%"/>
<define name="THROTTLE_SLEW_LIMITER" value="0.6" unit="s"/>
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(25)"/>
<define name="AUTO_PITCH_MIN_PITCH" value="RadOfDeg(-20)"/>
<!-- Climb loop (throttle) -->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_PITCH" value="0.0" unit="rad"/>
<define name="AUTO_THROTTLE_PGAIN" value="0.008" unit="%/(m/s)"/>
<define name="AUTO_THROTTLE_IGAIN" value="0.0"/>
<define name="AUTO_THROTTLE_DGAIN" value="0.001"/>
<!-- Climb loop (pitch) -->
<!-- magnitude of elevator movement on altitude change -->
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.15" unit="rad/(m/s)"/>
<define name="AUTO_PITCH_PGAIN" value="0.04"/>
<define name="AUTO_PITCH_IGAIN" value="0.01"/>
<define name="AUTO_PITCH_DGAIN" value="0.0"/>
<!-- Loiter and Dash trimming -->
<define name="AUTO_THROTTLE_LOITER_TRIM" value="0" unit="pprz_t"/>
<define name="AUTO_THROTTLE_DASH_TRIM" value="0" unit="pprz_t"/>
<define name="PITCH_LOITER_TRIM" value="0" unit="pprz_t"/>
<define name="PITCH_DASH_TRIM" value="0" unit="pprz_t"/>
</section>
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
<define name="COURSE_PGAIN" value="0.8"/>
<define name="COURSE_DGAIN" value="0.8"/>
<define name="COURSE_PRE_BANK_CORRECTION" value="1."/>
<define name="PITCH_MAX_SETPOINT" value="20" unit="deg"/>
<define name="PITCH_MIN_SETPOINT" value="-20" unit="deg"/>
<define name="PITCH_PGAIN" value="8000."/>
<define name="ROLL_MAX_SETPOINT" value="45" unit="deg"/>
<define name="ROLL_SLEW" value="0.1"/>
<define name="ROLL_ATTITUDE_GAIN" value="8000"/>
<define name="ROLL_RATE_GAIN" value="500."/>
<define name="PITCH_OF_ROLL" value="RadOfDeg(1.0)"/>
<define name="ELEVATOR_OF_ROLL" value="1250"/>
<define name="AILERON_OF_THROTTLE" value="0.0"/>
<define name="PITCH_DGAIN" value="6."/>
<define name="PITCH_IGAIN" value="100."/>
</section>
<section name="BAT">
<!-- FOR USE WITH A CURRENT SENSOR -->
<define name="CATASTROPHIC_BAT_LEVEL" value="7.5" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="8.5" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.3" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.6" unit="V"/>
</section>
<section name="MISC">
<define name="CLIMB_AIRSPEED" value="15." unit="m/s"/>
<define name="GLIDE_AIRSPEED" value="14." unit="m/s"/>
<define name="RACE_AIRSPEED" value="25." unit="m/s"/>
<define name="STALL_AIRSPEED" value="10." unit="m/s"/>
<define name="AIRSPEED_SETPOINT_SLEW" value="1" unit="s"/>
<define name="NOMINAL_AIRSPEED" value="16" unit="m/s"/>
<define name="MINIMUM_AIRSPEED" value="14." unit="m/s"/>
<define name="MAXIMUM_AIRSPEED" value="26." unit="m/s"/>
<define name="CARROT" value="3." unit="s"/>
<define name="GLIDE_RATIO" value="7."/>
<define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
<define name="CONTROL_FREQUENCY" value="60" unit="Hz"/>
<define name="XBEE_INIT" value="\"ATPL2\rATRN1\rATTT80\r\""/>
<define name="NO_XBEE_API_INIT" value="TRUE"/>
<define name="TRIGGER_DELAY" value="1."/>
<define name="DEFAULT_CIRCLE_RADIUS" value="60."/>
<!-- MIN_CIRCLE_RADIUS used and needed for spiral navigation function and panic autolanding turns-->
<define name="MIN_CIRCLE_RADIUS" value="40."/>
<!--UNLOCKED_HOME_MODE if set to TRUE means that HOME mode does not get stuck.
If not set before when you would enter home mode you had to flip a bit via the GCS to get out. -->
<define name="UNLOCKED_HOME_MODE" value="TRUE"/>
<!-- RC_LOST_MODE means that if your RC Transmitter signal is not received anymore in the autopilot, e.g. you switch it off
or fly a long range mission you define the wanted mode behaviour here.
If you do not define it, it defaults to flying to the flightplan HOME -->
<define name="RC_LOST_MODE" value="AP_MODE_AUTO2"/>
</section>
<section name="AGGRESSIVE" prefix="AGR_">
<define name="BLEND_START" value="40"/> <!-- Altitude Error to Initiate Aggressive Climb CANNOT BE ZERO!!-->
<define name="BLEND_END" value="10"/> <!-- Altitude Error to Blend Aggressive to Regular Climb Modes NOT ZERO!!-->
<define name="CLIMB_THROTTLE" value="1.0"/> <!-- Gaz for Aggressive Climb -->
<define name="CLIMB_PITCH" value="RadOfDeg(20)"/> <!-- Pitch for Aggressive Climb -->
<define name="DESCENT_THROTTLE" value="0.1"/> <!-- Gaz for Aggressive Decent -->
<define name="DESCENT_PITCH" value="RadOfDeg(-20)"/> <!-- Pitch for Aggressive Decent -->
<define name="CLIMB_NAV_RATIO" value="0.8"/> <!-- Percent Navigation for Altitude Error Equal to Start Altitude -->
<define name="DESCENT_NAV_RATIO" value="1.0"/>
</section>
<section name="NAV">
<define name="NAV_PITCH" value="0."/>
<define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
<define name="NAV_GROUND_SPEED_PGAIN" value="0.015"/>
<define name="NAV_FOLLOW_PGAIN" value="-0.05"/>
</section>
<section name="GLS_APPROACH" prefix="APP_">
<define name="ANGLE" value="5"/>
<define name="INTERCEPT_AF_TOD" value="10"/>
<define name="TARGET_SPEED" value="13"/>
</section>
<section name="FAILSAFE" prefix="FAILSAFE_">
<define name="DELAY_WITHOUT_GPS" value="1" unit="s"/>
<define name="DEFAULT_THROTTLE" value="0.8" unit="%"/>
<define name="DEFAULT_ROLL" value="10" unit="deg"/>
<define name="DEFAULT_PITCH" value="10" unit="deg"/>
<define name="HOME_RADIUS" value="100" unit="m"/>
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
</section>
<section name="DATALINK" prefix="DATALINK_">
<define name="DEVICE_TYPE" value="PPRZ"/>
<define name="DEVICE_ADDRESS" value="...."/>
</section>
<section name="GCS">
<define name="AC_ICON" value="flyingwing"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="100"/>
<define name="ALT_SHIFT_PLUS" value="10"/>
<define name="ALT_SHIFT_MINUS" value="-10"/>
<define name="SPEECH_NAME" value="DART"/>
</section>
<section name="SIMU">
<define name="WEIGHT" value ="1."/>
<define name="YAW_RESPONSE_FACTOR" value =".9"/>
<define name="PITCH_RESPONSE_FACTOR" value ="1.5"/>
<define name="ROLL_RESPONSE_FACTOR" value ="20."/>
</section>
</airframe>
+57
View File
@@ -0,0 +1,57 @@
# Hey Emacs, this is a -*- makefile -*-
#
# matek_f405_wing_v1.makefile
#
# http://www.mateksys.com/?portfolio=f405-wing
#
BOARD=matek_f405_wing
BOARD_VERSION=v1
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
ARCH=stm32
ARCH_L=f4
HARD_FLOAT=yes
$(TARGET).ARCHDIR = $(ARCH)
$(TARGET).LDSCRIPT=$(SRC_ARCH)/openpilot_revo.ld
# -----------------------------------------------------------------------
# default flash mode is via SWD
# other possibilities: DFU, DFU-UTIL, SWD, STLINK
FLASH_MODE ?= DFU-UTIL
#
# default LED configuration
#
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= none
GPS_LED ?=2
SYS_TIME_LED ?=1
#
# default uart configuration
#
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART3
MODEM_PORT ?= UART6
MODEM_BAUD ?= B57600
GPS_PORT ?= UART1
GPS_BAUD ?= B38400
#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm
+26
View File
@@ -0,0 +1,26 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="baro_bmp280" dir="sensors">
<doc>
<description>
Bosch-Sensortech BMP280xx pressure sensor
</description>
<configure name="BMP280_I2C_DEV" value="i2cX" description="select which i2c peripheral to use (default i2c1)"/>
<define name="BMP280_SLAVE_ADDR" value="BMP280_I2C_ADDR|BMP280_I2C_ADDR_ALT" description="i2c slave address (default BMP280_I2C_ADDR)"/>
<define name="BMP280_SYNC_SEND" description="flag to transmit the data as it is acquired"/>
</doc>
<header>
<file name="baro_bmp280_i2c.h"/>
</header>
<init fun="baro_bmp280_init()"/>
<periodic fun="baro_bmp280_periodic()" freq="50"/>
<event fun="baro_bmp280_event()"/>
<makefile target="ap">
<configure name="BMP280_I2C_DEV" default="i2c1" case="upper|lower"/>
<define name="USE_$(BMP280_I2C_DEV_UPPER)"/>
<define name="BMP280_I2C_DEV" value="$(BMP280_I2C_DEV_LOWER)"/>
<file name="baro_bmp280_i2c.c"/>
<file name="bmp280_i2c.c" dir="peripherals"/>
</makefile>
</module>
+36
View File
@@ -0,0 +1,36 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="board_matek_wing" dir="boards">
<doc>
<description>
Autoload several onboard sensors and subsystems
for the Matek F405 Wing board with proper configuration.
IMU MPU6000
Baro (BMP280)
OSD
Normal front of the board is on the servo S3-S8 servo connector
Normal up of the board is on STM32F405 side.
</description>
</doc>
<autoload name="imu" type="mpu6000"/>
<autoload name="spi" type="master"/>
<autoload name="osd_max7456" />
<autoload name="baro_bmp280_i2c" />
<makefile target="!sim|nps|fbw">
<!-- IMU CONFIGURATION -->
<configure name="IMU_MPU_SPI_DEV" value="spi1" case="upper|lower"/>
<configure name="IMU_MPU_SPI_SLAVE_IDX" value="SPI_SLAVE0"/>
<!-- BAROMETER BMP280 CONFIGURATION -->
<configure name="BMP280_I2C_DEV" value="i2c1" />
<configure name="BMP280_SLAVE_ADDR" value="BMP280_I2C_ADDR" />
<!-- OSD CONFIGURATION -->
<define name="MAX7456_SPI_DEV" value="spi2" />
<define name="MAX7456_SLAVE_IDX" value="SPI_SLAVE1" />
<define name="USE_MATEK_TYPE_OSD_CHIP" value="1" />
<define name="USE_PAL_FOR_OSD_VIDEO" value="1" />
<define name="OSD_USE_BARO_ALTITUDE" value="0" />
<define name="BARO_ALTITUDE_VAR" value="baro_alt" /> <!-- if non defined the default var is ''baro_alt'' -->
<define name="OSD_USE_MAG_COMPASS" value="0" />
</makefile>
</module>
-1
View File
@@ -23,7 +23,6 @@
<define name="MAX7456_SPI_DEV" value="$(MAX7456_SPI_DEV_LOWER)" />
<define name="MAX7456_SLAVE_IDX" value="$(MAX7456_SLAVE_IDX_UPPER)" />
<file name="max7456.c" />
<define name="USE_PAL_FOR_OSD_VIDEO" value="1" />
<define name="OSD_USE_EXTERNAL_SPRINTF" value="0" />
</makefile>
</module>
+51
View File
@@ -0,0 +1,51 @@
<?xml version="1.0"?>
<!-- $Id: openTX_radio_8ch.xml, Oct 2020
--
-- Chris Efstathiou 2008 - 2020
-- This file is part of paparazzi.
--
-- paparazzi is free software; you can redistribute it and/or modify
-- it under the terms of the GNU General Public License as published by
-- the Free Software Foundation; either version 2, or (at your option)
-- any later version.
--
-- paparazzi is distributed in the hope that it will be useful,
-- but WITHOUT ANY WARRANTY; without even the implied warranty of
-- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-- GNU General Public License for more details.
--
-- You should have received a copy of the GNU General Public License
-- along with paparazzi; see the file COPYING. If not, write to
-- the Free Software Foundation, 59 Temple Place - Suite 330,
-- Boston, MA 02111-1307, USA.
-- Attributes of root (Radio) tag :
-- name: name of RC
-- data_min: min width of a pulse to be considered as a data pulse
-- data_max: max width of a pulse to be considered as a data pulse
-- sync_min: min width of a pulse to be considered as a synchro pulse
-- sync_max: max width of a pulse to be considered as a synchro pulse
-- min, max and sync are expressed in micro-seconds
-- Attributes of channel tag :
-- ctl: name of the command on the transmitter - only for displaying
-- no: order in the PPM frame
-- function: logical command
-- averaged: channel filtered through several frames (for discrete commands)
-- min: minimum pulse length (micro-seconds)
-- max: maximum pulse length (micro-seconds)
-- neutral: neutral pulse length (micro-seconds)
-- Note: a command may be reversed by exchanging min and max values
-->
<!DOCTYPE radio SYSTEM "/radio.dtd">
<radio name="X8_OPEN9X" data_min="700" data_max="2200" sync_min="2500" sync_max="18000" pulse_type="NEGATIVE">
<channel ctl="A" function="ROLL" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="B" function="PITCH" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="C" function="THROTTLE" min="988" neutral="988" max="2012" average="0"/>
<channel ctl="D" function="YAW" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="E" function="MODE" min="988" neutral="1500" max="2012" average="10"/>
<channel ctl="E" function="PARACHUTE" min="988" neutral="988" max="2012" average="10"/>
<channel ctl="F" function="AUX1" min="988" neutral="1500" max="2012" average="0"/>
<channel ctl="G" function="AUX2" min="988" neutral="1500" max="2012" average="0"/>
</radio>
@@ -0,0 +1,99 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "/telemetry.dtd">
<telemetry>
<process name="Ap">
<mode name="default">
<message name="ALIVE" period="5.0"/>
<message name="ATTITUDE" period="0.55"/>
<message name="ESTIMATOR" period="0.60"/>
<message name="DL_VALUE" period="0.65"/>
<message name="WP_MOVED" period="0.75"/>
<message name="GPS" period="1.25"/>
<message name="ENERGY" period="1.35"/>
<message name="SEGMENT" period="1.45"/>
<message name="WEATHER" period="1.65"/>
<message name="BMP_STATUS" period="1.75"/> <!-- BARO BMP280 DATA -->
<message name="CIRCLE" period="2.05"/>
<message name="DESIRED" period="2.25"/>
<message name="NAVIGATION" period="3.05"/>
<message name="PPRZ_MODE" period="5.05"/>
<message name="GPS_SOL" period="5.25"/>
<message name="NAVIGATION_REF" period="9.35"/>
</mode>
<mode name="minimal">
<message name="ALIVE" period="5.0"/>
<message name="ATTITUDE" period="0.65"/>
<message name="ENERGY" period="0.95"/>
<message name="CAM_POINT" period="1.05"/>
<message name="GPS" period="1.25"/>
<message name="ESTIMATOR" period="1.35"/>
<message name="WP_MOVED" period="1.45"/>
<message name="DL_VALUE" period="1.55"/>
<message name="SURVEY" period="2.05"/>
<message name="CIRCLE" period="2.15"/>
<message name="DESIRED" period="2.25"/>
<message name="SEGMENT" period="2.35"/>
<message name="NAVIGATION" period="3.05"/>
<message name="PPRZ_MODE" period="5.25"/>
<message name="GPS_SOL" period="5.45"/>
<message name="NAVIGATION_REF" period="9.05"/>
</mode>
<mode name="extremal">
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="0.5"/>
<message name="CAM_POINT" period="1.0"/>
<message name="GPS" period="5.1"/>
<message name="ESTIMATOR" period="5.2"/>
<message name="NAVIGATION" period="5.4"/>
<message name="PPRZ_MODE" period="5.5"/>
<message name="ENERGY" period="10.1"/>
<message name="DESIRED" period="10.2"/>
</mode>
<mode name="raw_sensors">
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_ACCEL_RAW" period=".2"/>
<message name="IMU_GYRO_RAW" period=".5"/>
<message name="IMU_MAG_RAW" period=".3"/>
<message name="BARO_RAW" period="0.5"/>
</mode>
<mode name="scaled_sensors">
<message name="DL_VALUE" period="0.5"/>
<message name="ALIVE" period="2.1"/>
<message name="IMU_GYRO" period=".075"/>
<message name="IMU_ACCEL" period=".075"/>
<message name="IMU_MAG" period=".1"/>
</mode>
<mode name="debug_imu">
<message name="ATTITUDE" period="0.1"/>
<message name="ALIVE" period="5"/>
<message name="GPS" period="5.1"/>
<message name="ESTIMATOR" period="5.3"/>
<message name="ENERGY" period="10.1"/>
<message name="DESIRED" period="10.2"/>
<message name="NAVIGATION" period="5.4"/>
<message name="PPRZ_MODE" period="5.5"/>
<message name="STATE_FILTER_STATUS" period="5."/>
<message name="IMU_ACCEL" period=".5"/>
<message name="IMU_GYRO" period=".5"/>
<message name="IMU_MAG" period=".5"/>
<message name="IMU_ACCEL_RAW" period=".5"/>
<message name="IMU_GYRO_RAW" period=".5"/>
<message name="IMU_MAG_RAW" period=".5"/>
</mode>
</process>
<process name="Fbw">
<mode name="default">
<message name="COMMANDS" period="5"/>
<message name="FBW_STATUS" period="2"/>
<message name="ACTUATORS" period="5"/> <!-- For trimming -->
</mode>
<mode name="debug">
<message name="PPM" period="0.5"/>
<message name="RC" period="0.5"/>
<message name="COMMANDS" period="0.5"/>
<message name="FBW_STATUS" period="1"/>
<message name="ACTUATORS" period="5"/> <!-- For trimming -->
</mode>
</process>
</telemetry>
+468
View File
@@ -0,0 +1,468 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#ifndef CONFIG_MATEK_F405_WING_1_0_H
#define CONFIG_MATEK_F405_WING_1_0_H
#define BOARD_MATEK_F405_WING
/* The Matek F405 Wing autopilot has a 8MHz external clock and 168MHz internal. */
#define EXT_CLK 8000000
#define AHB_CLK 168000000
// Onboard LEDs
/* STAT blue, on PB5 */
#ifndef USE_LED_1
#define USE_LED_1 1
#endif
#define LED_1_GPIO GPIOA
#define LED_1_GPIO_PIN GPIO14
#define LED_1_GPIO_ON gpio_clear
#define LED_1_GPIO_OFF gpio_set
#define LED_1_AFIO_REMAP ((void)0)
/* WARN red, on PB4 */
#ifndef USE_LED_2
#define USE_LED_2 1
#endif
#define LED_2_GPIO GPIOA
#define LED_2_GPIO_PIN GPIO13
#define LED_2_GPIO_ON gpio_clear
#define LED_2_GPIO_OFF gpio_set
#define LED_2_AFIO_REMAP ((void)0)
// LED STRIP 2812
#ifndef USE_LED_3
#define USE_LED_3 1
#endif
#define LED_3_GPIO GPIOA
#define LED_3_GPIO_PIN GPIO15
#define LED_3_GPIO_ON gpio_clear
#define LED_3_GPIO_OFF gpio_set
#define LED_3_AFIO_REMAP ((void)0)
// BEEPER
#ifndef USE_LED_4
#define USE_LED_4 1
#endif
#define LED_4_GPIO GPIOC
#define LED_4_GPIO_PIN GPIO15
#define LED_4_GPIO_ON gpio_clear
#define LED_4_GPIO_OFF gpio_set
#define LED_4_AFIO_REMAP ((void)0)
/* Default actuators driver */
#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
#define ActuatorsDefaultInit() ActuatorsPwmInit()
#define ActuatorsDefaultCommit() ActuatorsPwmCommit()
#define VBUS_GPIO GPIOC
#define VBUS_GPIO_PIN GPIO13
/* UART */
//CAN BE USED AS GPS SERIAL PORT
#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
// UART 2 RX INPUT IS USED AS THE PPM INPUT THUS I WILL USE THE TX OUTPUT AS ADC INPUT
#define UART2_GPIO_AF GPIO_AF8
#define UART2_GPIO_PORT_TX GPIOA
#define UART2_GPIO_TX GPIO2
#define UART2_GPIO_PORT_RX GPIOA
#define UART2_GPIO_RX GPIO3
#define UART3_GPIO_AF GPIO_AF8
#define UART3_GPIO_PORT_TX GPIOC
#define UART3_GPIO_TX GPIO10
#define UART3_GPIO_PORT_RX GPIOC
#define UART3_GPIO_RX GPIO11
#define UART4_GPIO_AF GPIO_AF8
#define UART4_GPIO_PORT_TX GPIOA
#define UART4_GPIO_TX GPIO0
#define UART4_GPIO_PORT_RX GPIOA
#define UART4_GPIO_RX GPIO1
#define UART5_GPIO_AF GPIO_AF8
#define UART5_GPIO_PORT_TX GPIOC
#define UART5_GPIO_TX GPIO12
#define UART5_GPIO_PORT_RX GPIOD
#define UART5_GPIO_RX GPIO2
// CAN BE USED AS A MODEM SERIAL PORT
#define UART6_GPIO_AF GPIO_AF8
#define UART6_GPIO_PORT_TX GPIOC
#define UART6_GPIO_TX GPIO6
#define UART6_GPIO_PORT_RX GPIOC
#define UART6_GPIO_RX GPIO7
// SPI1, MPU6000 ON SPI1
#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
#define SPI1_GPIO_PORT_NSS GPIOA
#define SPI1_GPIO_NSS GPIO4
#define SPI_SELECT_SLAVE0_PORT GPIOA
#define SPI_SELECT_SLAVE0_PIN GPIO4
// SPI2 IS USED FOR THE MAX7456 OSD
#define SPI2_GPIO_AF GPIO_AF5
#define SPI2_GPIO_PORT_SCK GPIOB
#define SPI2_GPIO_SCK GPIO13
#define SPI2_GPIO_PORT_MISO GPIOC
#define SPI2_GPIO_MISO GPIO2
#define SPI2_GPIO_PORT_MOSI GPIOC
#define SPI2_GPIO_MOSI GPIO3
#define SPI2_GPIO_PORT_NSS GPIOB
#define SPI2_GPIO_NSS GPIO12
#define SPI_SELECT_SLAVE1_PORT GPIOB
#define SPI_SELECT_SLAVE1_PIN GPIO12
// SDCARD ON SPI3
#define SPI3_GPIO_AF GPIO_AF5
#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
#define SPI3_GPIO_PORT_NSS GPIOC
#define SPI3_GPIO_NSS GPIO14
#define SPI_SELECT_SLAVE2_PORT GPIOC
#define SPI_SELECT_SLAVE2_PIN GPIO14
/* I2C mapping */
/* HMC5883L mag on I2C1 with DRDY on PB7 */
/* MS5611 baro on I2C1 */
#define I2C1_GPIO_PORT GPIOB
#define I2C1_GPIO_SCL GPIO8
#define I2C1_GPIO_SDA GPIO9
#define I2C2_GPIO_PORT GPIOB
#define I2C2_GPIO_SCL GPIO10
#define I2C2_GPIO_SDA GPIO11
// ADC
/* Onboard ADCs */
/*
ADC1 PC2/ADC1,2,3 channel 12 (Voltage input 3.3v max)
ADC2 PC1/ADC1,2,3 channel 11 (Current input 3.3v max)
ADC3 PA3/ADC1,2,3 channel 3
ADC4 PA2/ADC1,2,3 channel 2
*/
/* provide defines that can be used to access the ADC_x in the code or airframe file
* these directly map to the index number of the 4 adc channels defined above
* 4th (index 3) is used for bat monitoring by default
*/
#define USE_AD_TIM2 1
#ifndef USE_ADC_1
#define USE_ADC_1 1
#endif
#ifndef USE_ADC_2
#define USE_ADC_2 1
#endif
#ifndef USE_ADC_3
#define USE_ADC_3 1
#endif
#ifndef USE_ADC_4
#define USE_ADC_4 1
#endif
// POWER SUPPLY VOLTAGE MEASUREMENT INPUT
#if USE_ADC_1
#define AD1_1_CHANNEL 10
#define ADC_1 AD1_1
#define ADC_1_GPIO_PORT GPIOC
#define ADC_1_GPIO_PIN GPIO0
#endif
// CURRENT MEASUREMENT INPUT
#if USE_ADC_2
#define AD1_2_CHANNEL 11
#define ADC_2 AD1_2
#define ADC_2_GPIO_PORT GPIOC
#define ADC_2_GPIO_PIN GPIO1
#ifndef CURRENT_ADC_IN
#define CURRENT_ADC_IN ADC_2
#endif
#endif
// RSSI MEASUREMENT INPUT
#if USE_ADC_3
#define AD1_3_CHANNEL 15
#define ADC_3 AD1_3
#define ADC_3_GPIO_PORT GPIOC
#define ADC_3_GPIO_PIN GPIO5
#endif
// FREE, LABELED AS UART2 TX PIN
#if USE_ADC_4
#define AD1_4_CHANNEL 2
#define ADC_4 AD1_4
#define ADC_4_GPIO_PORT GPIOA
#define ADC_4_GPIO_PIN GPIO2
#endif
/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
#ifndef ADC_CHANNEL_VSUPPLY
#define ADC_CHANNEL_VSUPPLY ADC_1
#endif
#ifndef CURRENT_ADC_IN
#define CURRENT_ADC_IN ADC_2
#endif
/* no voltage divider on board, adjust VoltageOfAdc in airframe file */
#define DefaultVoltageOfAdc(adc) (0.008830925*adc)
#define DefaultMilliAmpereOfAdc(adc) (25*adc)
#define UART2_RX 1
#define SERVO9_PWM_OUT 2
#if defined(RADIO_CONTROL_PPM_PIN) && RADIO_CONTROL_PPM_PIN == UART2_RX
// THE PPM INPUT IS ALSO THE UART2 RX
#define USE_PPM_TIM9 1
#define PPM_CHANNEL TIM_IC2
#define PPM_TIMER_INPUT TIM_IC_IN_TI2
#define PPM_IRQ NVIC_TIM1_BRK_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
#else
#define USE_PPM_TIM1 1
#define PPM_CHANNEL TIM_IC1
#define PPM_TIMER_INPUT TIM_IC_IN_TI1
#define PPM_IRQ NVIC_TIM1_CC_IRQ
// Capture/Compare InteruptEnable and InterruptFlag
#define PPM_CC_IE TIM_DIER_CC1IE
#define PPM_CC_IF TIM_SR_CC1IF
#define PPM_GPIO_PORT GPIOA
#define PPM_GPIO_PIN GPIO8
#define PPM_GPIO_AF GPIO_AF1
#endif
// SERVO DEFINITIONS
#define PWM_USE_TIM1 0
#define PWM_USE_TIM3 1
#define PWM_USE_TIM4 1
#define PWM_USE_TIM8 1
#define PWM_USE_TIM12 1
#define USE_PWM1 1
#define USE_PWM2 1
#define USE_PWM3 1
#define USE_PWM4 1
#define USE_PWM5 1
#define USE_PWM6 1
#define USE_PWM7 1
#define USE_PWM8 1
#define USE_PWM9 0
// PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
#if USE_PWM1
#define PWM_SERVO_1 0
#define PWM_SERVO_1_TIMER TIM4
#define PWM_SERVO_1_GPIO GPIOB
#define PWM_SERVO_1_PIN GPIO7
#define PWM_SERVO_1_AF GPIO_AF2
#define PWM_SERVO_1_OC TIM_OC2
#define PWM_SERVO_1_OC_BIT (1<<1)
#else
#define PWM_SERVO_1_OC_BIT 0
#endif
#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
#if USE_PWM3
#define PWM_SERVO_3 2
#define PWM_SERVO_3_TIMER TIM3
#define PWM_SERVO_3_GPIO GPIOB
#define PWM_SERVO_3_PIN GPIO0
#define PWM_SERVO_3_AF GPIO_AF2
#define PWM_SERVO_3_OC TIM_OC3
#define PWM_SERVO_3_OC_BIT (1<<2)
#else
#define PWM_SERVO_3_OC_BIT 0
#endif
#if USE_PWM4
#define PWM_SERVO_4 3
#define PWM_SERVO_4_TIMER TIM3
#define PWM_SERVO_4_GPIO GPIOB
#define PWM_SERVO_4_PIN GPIO1
#define PWM_SERVO_4_AF GPIO_AF2
#define PWM_SERVO_4_OC TIM_OC4
#define PWM_SERVO_4_OC_BIT (1<<3)
#else
#define PWM_SERVO_4_OC_BIT 0
#endif
#if USE_PWM5
#define PWM_SERVO_5 4
#define PWM_SERVO_5_TIMER TIM8
#define PWM_SERVO_5_GPIO GPIOC
#define PWM_SERVO_5_PIN GPIO8
#define PWM_SERVO_5_AF GPIO_AF3
#define PWM_SERVO_5_OC TIM_OC3
#define PWM_SERVO_5_OC_BIT (1<<2)
#else
#define PWM_SERVO_5_OC_BIT 0
#endif
#if USE_PWM6
#define PWM_SERVO_6 5
#define PWM_SERVO_6_TIMER TIM8
#define PWM_SERVO_6_GPIO GPIOC
#define PWM_SERVO_6_PIN GPIO9
#define PWM_SERVO_6_AF GPIO_AF3
#define PWM_SERVO_6_OC TIM_OC4
#define PWM_SERVO_6_OC_BIT (1<<3)
#else
#define PWM_SERVO_6_OC_BIT 0
#endif
#if USE_PWM7
#define PWM_SERVO_7 6
#define PWM_SERVO_7_TIMER TIM12
#define PWM_SERVO_7_GPIO GPIOB
#define PWM_SERVO_7_PIN GPIO14
#define PWM_SERVO_7_AF GPIO_AF9
#define PWM_SERVO_7_OC TIM_OC1
#define PWM_SERVO_7_OC_BIT (1<<0)
#else
#define PWM_SERVO_7_OC_BIT 0
#endif
#if USE_PWM8
#define PWM_SERVO_8 7
#define PWM_SERVO_8_TIMER TIM12
#define PWM_SERVO_8_GPIO GPIOB
#define PWM_SERVO_8_PIN GPIO15
#define PWM_SERVO_8_AF GPIO_AF9
#define PWM_SERVO_8_OC TIM_OC2
#define PWM_SERVO_8_OC_BIT (1<<1)
#else
#define PWM_SERVO_8_OC_BIT 0
#endif
#if USE_PWM9
#define PWM_SERVO_9 8
#define PWM_SERVO_9_TIMER TIM1
#define PWM_SERVO_9_GPIO GPIOA
#define PWM_SERVO_9_PIN GPIO8
#define PWM_SERVO_9_AF GPIO_AF1
#define PWM_SERVO_9_OC TIM_OC1
#define PWM_SERVO_9_OC_BIT (1<<0)
#else
#define PWM_SERVO_9_OC_BIT 0
#endif
// servos 1-2 on TIM4
#define PWM_TIM4_CHAN_MASK (PWM_SERVO_1_OC_BIT | PWM_SERVO_2_OC_BIT)
// servos 3-4 on TIM3
#define PWM_TIM3_CHAN_MASK (PWM_SERVO_3_OC_BIT | PWM_SERVO_4_OC_BIT)
// servos 5-6 on TIM8
#define PWM_TIM8_CHAN_MASK (PWM_SERVO_5_OC_BIT | PWM_SERVO_6_OC_BIT)
// servos 7-8 on TIM12
#define PWM_TIM12_CHAN_MASK (PWM_SERVO_7_OC_BIT | PWM_SERVO_8_OC_BIT)
// servo 9 on TIM1
#if USE_PWM9
#define PWM_TIM1_CHAN_MASK (PWM_SERVO_9_OC_BIT)
#endif
/*
* Spektrum
*/
/* The line that is pulled low at power up to initiate the bind process */
#define SPEKTRUM_BIND_PIN GPIO0
#define SPEKTRUM_BIND_PIN_PORT GPIOB
#define SPEKTRUM_UART1_RCC RCC_USART1
#define SPEKTRUM_UART1_BANK GPIOA
#define SPEKTRUM_UART1_PIN GPIO10
#define SPEKTRUM_UART1_AF GPIO_AF7
#define SPEKTRUM_UART1_IRQ NVIC_USART1_IRQ
#define SPEKTRUM_UART1_ISR usart1_isr
#define SPEKTRUM_UART1_DEV USART1
#define SPEKTRUM_UART2_RCC RCC_USART2
#define SPEKTRUM_UART2_BANK GPIOA
#define SPEKTRUM_UART2_PIN GPIO3
#define SPEKTRUM_UART2_AF GPIO_AF8
#define SPEKTRUM_UART2_IRQ NVIC_USART2_IRQ
#define SPEKTRUM_UART2_ISR usart2_isr
#define SPEKTRUM_UART2_DEV USART2
#define SPEKTRUM_UART5_RCC RCC_UART5
#define SPEKTRUM_UART5_BANK GPIOD
#define SPEKTRUM_UART5_PIN GPIO2
#define SPEKTRUM_UART5_AF GPIO_AF8
#define SPEKTRUM_UART5_IRQ NVIC_UART5_IRQ
#define SPEKTRUM_UART5_ISR uart5_isr
#define SPEKTRUM_UART5_DEV UART5
#endif // CONFIG_MATEK_F405_WING_1_0_H
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,78 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, see
* <http://www.gnu.org/licenses/>.
*
*/
/**
* @file modules/sensors/baro_bmp280.c
* Bosch BMP280 I2C sensor interface.
*
* This reads the values for pressure and temperature from the Bosch BMP280 sensor through I2C.
*/
#include "baro_bmp280_i2c.h"
#include "subsystems/abi.h"
#include "mcu_periph/uart.h"
#include "pprzlink/messages.h"
#include "subsystems/datalink/downlink.h"
#include "math/pprz_isa.h"
/** default slave address */
#ifndef BMP280_SLAVE_ADDR
#define BMP280_SLAVE_ADDR BMP280_I2C_ADDR
#endif
float baro_alt = 0;
bool baro_alt_valid = 0;
struct Bmp280_I2c baro_bmp280;
void baro_bmp280_init(void)
{
bmp280_i2c_init(&baro_bmp280, &BMP280_I2C_DEV, BMP280_SLAVE_ADDR);
}
void baro_bmp280_periodic(void)
{
bmp280_i2c_periodic(&baro_bmp280);
}
void baro_bmp280_event(void)
{
bmp280_i2c_event(&baro_bmp280);
if (baro_bmp280.data_available) {
uint32_t now_ts = get_sys_time_usec();
// send ABI message
AbiSendMsgBARO_ABS(BARO_BMP_SENDER_ID, now_ts, baro_bmp280.pressure);
AbiSendMsgTEMPERATURE(BARO_BMP_SENDER_ID, baro_bmp280.temperature);
baro_bmp280.data_available = false;
baro_alt = pprz_isa_altitude_of_pressure((float)baro_bmp280.pressure);
baro_alt_valid = TRUE;
#ifdef BMP280_SYNC_SEND
int32_t up = (int32_t)(baro_alt * 100.0);
int32_t ut = (int32_t) baro_bmp280.raw_temperature;
int32_t p = (int32_t) baro_bmp280.pressure;
int32_t t = (int32_t)(baro_bmp280.temperature);
DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, &up, &ut, &p, &t);
#endif
}
}
@@ -0,0 +1,43 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, see
* <http://www.gnu.org/licenses/>.
*
*/
/**
* @file modules/sensors/baro_bmp280.h
* Bosch BMP280 I2C sensor interface.
*
* This reads the values for pressure and temperature from the Bosch BMP280 sensor through I2C.
*/
#ifndef BARO_BMP280_H
#define BARO_BMP280_H
#include "peripherals/bmp280_i2c.h"
extern struct Bmp280_I2c baro_bmp280;
extern float baro_alt;
extern bool baro_alt_valid;
void baro_bmp280_init(void);
void baro_bmp280_periodic(void);
void baro_bmp280_event(void);
#endif
+248
View File
@@ -0,0 +1,248 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file peripherals/bmp280_i2c.c
* @brief Sensor driver for BMP280 sensor via I2C
*
*
*/
#include "peripherals/bmp280_i2c.h"
/** local function to extract raw data from i2c buffer
* and compute compensation with selected precision
*/
static void parse_sensor_data(struct Bmp280_I2c *bmp);
static void parse_calib_data(struct Bmp280_I2c *bmp);
PRINT_CONFIG_MSG("BMP280 uses double precision compensation")
static double compensate_pressure(struct Bmp280_I2c *bmp);
static double compensate_temperature(struct Bmp280_I2c *bmp);
int64_t t_fine;
// init function
void bmp280_i2c_init(struct Bmp280_I2c *bmp, struct i2c_periph *i2c_p, uint8_t addr)
{
// set i2c_peripheral
bmp->i2c_p = i2c_p;
// slave address
bmp->i2c_trans.slave_addr = addr;
// set initial status: Done
bmp->i2c_trans.status = I2CTransDone;
bmp->data_available = false;
bmp->initialized = false;
bmp->status = BMP280_STATUS_UNINIT;
}
// Start new measurement if sensor ready
void bmp280_i2c_periodic(struct Bmp280_I2c *bmp)
{
if (bmp->i2c_trans.status != I2CTransDone) {
return; // transaction not finished
}
switch (bmp->status) {
case BMP280_STATUS_UNINIT:
bmp->data_available = false;
bmp->initialized = false;
bmp->status = BMP280_STATUS_GET_CALIB;
break;
case BMP280_STATUS_GET_CALIB:
// request calibration data
bmp->i2c_trans.buf[0] = BMP280_CALIB_LSB_DATA_ADDR;
i2c_transceive(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 1, BMP280_CALIB_DATA_LEN);
break;
case BMP280_STATUS_CONFIGURE:
// From datasheet, recommended config for drone usecase:
// osrs_p = 8, osrs_t = 1
// IIR filter = 2 (note: this one doesn't exist...)
bmp->i2c_trans.buf[0] = BMP280_CTRL_MEAS_REG_ADDR;
bmp->i2c_trans.buf[1] = (BMP280_OVERSAMPLING_1X_T | BMP280_OVERSAMPLING_8X_P | BMP280_POWER_NORMAL_MODE);
bmp->i2c_trans.buf[2] = BMP280_CONFIG_REG_ADDR;
bmp->i2c_trans.buf[3] = (BMP280_INACTIVITY_62_5_MS | BMP280_IIR_FILTER_COEFF_2);
i2c_transmit(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, (BMP280_CONFIG_LEN * 2));
break;
case BMP280_STATUS_READ_STATUS_REG:
// READ THE STATUS BYTE
bmp->i2c_trans.buf[0] = BMP280_STATUS_REG_ADDR;
i2c_transceive(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 1, 1);
break;
case BMP280_STATUS_READ_DATA_REGS:
// READ ALL 6 DATA REGISTERS
bmp->i2c_trans.buf[0] = BMP280_DATA_START_REG_ADDR;
i2c_transceive(bmp->i2c_p, &bmp->i2c_trans, bmp->i2c_trans.slave_addr, 1, BMP280_P_T_DATA_LEN);
break;
default:
break;
}
}
void bmp280_i2c_event(struct Bmp280_I2c *bmp)
{
if (bmp->i2c_trans.status == I2CTransSuccess) {
switch (bmp->status) {
case BMP280_STATUS_GET_CALIB:
// compute calib
parse_calib_data(bmp);
bmp->status = BMP280_STATUS_CONFIGURE;
break;
case BMP280_STATUS_CONFIGURE:
// nothing else to do, start reading
bmp->status = BMP280_STATUS_READ_STATUS_REG;
bmp->initialized = true;
break;
case BMP280_STATUS_READ_STATUS_REG:
// check status byte
if ((bmp->i2c_trans.buf[0] & (BMP280_EOC_BIT | BMP280_NVRAM_COPY_BIT)) == 0) {
bmp->status = BMP280_STATUS_READ_DATA_REGS;
}
break;
case BMP280_STATUS_READ_DATA_REGS:
// parse sensor data, compensate temperature first, then pressure
parse_sensor_data(bmp);
compensate_temperature(bmp);
compensate_pressure(bmp);
bmp->data_available = true;
bmp->status = BMP280_STATUS_READ_STATUS_REG;
break;
default:
bmp->status = BMP280_STATUS_GET_CALIB; // just to avoid the compiler's warning message
break;
}
bmp->i2c_trans.status = I2CTransDone;
} else if (bmp->i2c_trans.status == I2CTransFailed) {
/* try again */
if (!bmp->initialized) {
bmp->status = BMP280_STATUS_UNINIT;
}
bmp->i2c_trans.status = I2CTransDone;
}
return;
}
static void parse_sensor_data(struct Bmp280_I2c *bmp)
{
/* Temporary variables to store the sensor data */
uint32_t data_xlsb;
uint32_t data_lsb;
uint32_t data_msb;
// BMP280 HAS THE 6 DATA REGISTERS START AT F7 AND GOING UP TO FC MSB FIRST THEN LSB AND LAST THE XLSB BYTE.
// THE FIRST THREE BYTES ARE THE PRESSURE AND THE NEXT 3 THE TEMPERATURE.
/* Store the parsed register values for pressure data */
data_msb = (uint32_t)bmp->i2c_trans.buf[0] << 16;
data_lsb = (uint32_t)bmp->i2c_trans.buf[1] << 8;
data_xlsb = (uint32_t)bmp->i2c_trans.buf[2];
bmp->raw_pressure = (int32_t)((data_msb | data_lsb | data_xlsb) >> 4);
/* Store the parsed register values for temperature data */
data_msb = (uint32_t)bmp->i2c_trans.buf[3] << 16;
data_lsb = (uint32_t)bmp->i2c_trans.buf[4] << 8;
data_xlsb = (uint32_t)bmp->i2c_trans.buf[5];
bmp->raw_temperature = (int32_t)((data_msb | data_lsb | data_xlsb) >> 4);
}
/**
* @brief This internal API is used to parse the calibration data, compensates
* it and store it in device structure (float version)
*/
static void parse_calib_data(struct Bmp280_I2c *bmp)
{
uint8_t *data = (uint8_t *)bmp->i2c_trans.buf; // we know that this buffer will not be modified during this call
bmp->calib.dig_t1 = BMP280_CONCAT_BYTES(data[1], data[0]);
bmp->calib.dig_t2 = (int16_t)BMP280_CONCAT_BYTES(data[3], data[2]);
bmp->calib.dig_t3 = (int16_t)BMP280_CONCAT_BYTES(data[5], data[4]);
bmp->calib.dig_p1 = BMP280_CONCAT_BYTES(data[7], data[6]);
bmp->calib.dig_p2 = (int16_t)BMP280_CONCAT_BYTES(data[9], data[8]);
bmp->calib.dig_p3 = (int16_t)BMP280_CONCAT_BYTES(data[11], data[10]);
bmp->calib.dig_p4 = (int16_t)BMP280_CONCAT_BYTES(data[13], data[12]);
bmp->calib.dig_p5 = (int16_t)BMP280_CONCAT_BYTES(data[15], data[14]);
bmp->calib.dig_p6 = (int16_t)BMP280_CONCAT_BYTES(data[17], data[16]);
bmp->calib.dig_p7 = (int16_t)BMP280_CONCAT_BYTES(data[19], data[18]);
bmp->calib.dig_p8 = (int16_t)BMP280_CONCAT_BYTES(data[21], data[20]);
bmp->calib.dig_p9 = (int16_t)BMP280_CONCAT_BYTES(data[23], data[22]);
return;
}
/**
* @brief This internal API is used to compensate the raw temperature data and
* return the compensated temperature data in float data type.
*/
static double compensate_temperature(struct Bmp280_I2c *bmp)
{
double var1;
double var2;
var1 = (((double)bmp->raw_temperature / 16384.0) - ((double)bmp->calib.dig_t1 / 1024.0)) * ((double)bmp->calib.dig_t2);
var2 = ((double)bmp->raw_temperature / 131072.0) - ((double)bmp->calib.dig_t1 / 8192.0);
var2 = (var2 * var2) * (double)bmp->calib.dig_t3;
t_fine = (int64_t)(var1 + var2);
/* Store t_lin in dev. structure for pressure calculation */
bmp->calib.t_fine = t_fine;
/* Store compensated temperature in float in structure */
bmp->temperature = (((var1 + var2) / 5120.f) * 100);
return (double)bmp->temperature;
}
/**
* @brief This internal API is used to compensate the raw pressure data and
* return the compensated pressure data in integer data type.
*/
static double compensate_pressure(struct Bmp280_I2c *bmp)
{
double var1;
double var2;
double p;
var1 = ((double)t_fine / 2) - 64000.0;
var2 = (var1 * var1 * (double)bmp->calib.dig_p5) / 32768.0;
var2 = var2 + (var1 * (double)bmp->calib.dig_p5 * 2.0);
var2 = (var2 / 4.0) + ((double)bmp->calib.dig_p4 * 65536.0);
var1 = (((double)bmp->calib.dig_p3 * var1 * (var1 / 524288.0)) + ((double)bmp->calib.dig_p2 * var1)) / 524288.0;
var1 = (1 + (var1 / 32768.0)) * (double)bmp->calib.dig_p1;
p = 1048576.0 - (double)bmp->raw_pressure;
p = (p - (var2 / 4096.0)) * (6250.0 / var1);
var1 = ((double)bmp->calib.dig_p9 * p) * (p / 2147483648.0);
var2 = (p * ((double)bmp->calib.dig_p8)) / 32768.0;
p = p + ((var1 + var2 + (double)bmp->calib.dig_p7) / 16.0);
bmp->pressure = p;
return (p);
}
+53
View File
@@ -0,0 +1,53 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file peripherals/bmp280_i2c.h
* @brief Sensor driver for BMP280 sensor via I2C
*
*
*/
#ifndef BMP280_I2C_H
#define BMP280_I2C_H
/* Header includes */
#include "peripherals/bmp280_regs.h"
#include "mcu_periph/i2c.h"
struct Bmp280_I2c {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
enum Bmp280Status status; ///< state machine status
bool initialized; ///< config done flag
volatile bool data_available; ///< data ready flag
struct bmp280_reg_calib_data calib; ///< calibration data
uint32_t raw_pressure; ///< uncompensated pressure
uint32_t raw_temperature; ///< uncompensated temperature
float pressure; ///< pressure in Pascal
float temperature; ///< temperature in deg Celcius
};
extern void bmp280_i2c_read_eeprom_calib(struct Bmp280_I2c *bmp);
extern void bmp280_i2c_init(struct Bmp280_I2c *bmp, struct i2c_periph *i2c_p, uint8_t addr);
extern void bmp280_i2c_periodic(struct Bmp280_I2c *bmp);
extern void bmp280_i2c_event(struct Bmp280_I2c *bmp);
#endif /* BMP280_I2C_H */
+174
View File
@@ -0,0 +1,174 @@
/*
* Chris Efstathiou hendrixgr@gmail.com
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file peripherals/bmp3_regs.h
* @brief Sensor driver for BMP280 sensor register definition
*
* Modified for Paparazzi from SDP3 driver from BoshSensortec
* see https://github.com/BoschSensortec/BMP280-Sensor-API
* for original code and license
*
*/
#ifndef BMP280_REGS_H
#define BMP280_REGS_H
#include "std.h"
// I2C addresses (8 bits)
#define BMP280_I2C_ADDR 0xEC
#define BMP280_I2C_ADDR_ALT 0xEE
/**\name BMP280 chip identifier */
#define BMP280_CHIP_ID 0x50
// CALIBRATION REGISTER ADDRESSES
#define BMP280_CALIB_LSB_DATA_ADDR 0x88
#define BMP280_CALIB_DATA_LEN 24
#define BMP280_DIG_T1_UINT 0x88
#define BMP280_DIG_T2_INT 0x8A
#define BMP280_DIG_T3_INT 0x8C
#define BMP280_DIG_P1_UINT 0x8E
#define BMP280_DIG_P2_INT 0x90
#define BMP280_DIG_P3_INT 0x92
#define BMP280_DIG_P4_INT 0x94
#define BMP280_DIG_P5_INT 0x96
#define BMP280_DIG_P6_INT 0x98
#define BMP280_DIG_P7_INT 0x9A
#define BMP280_DIG_P8_INT 0x9C
#define BMP280_DIG_P9_INT 0x9E
// CONTROL AND VALUES REGISTER ADDRESSES
#define BMP280_CONFIG_ADDR 0xF4
#define BMP280_CONFIG_LEN 0x02
#define BMP280_DATA_START_REG_ADDR 0xF7
#define BMP280_P_T_DATA_LEN 6
#define BMP280_P_DATA_LEN 3
#define BMP280_T_DATA_LEN 3
#define BMP280_CHIP_ID_REG_ADDR 0xD0
#define BMP280_RESET_REG_ADDR 0xF3
#define BMP280_STATUS_REG_ADDR 0xF3
#define BMP280_CTRL_MEAS_REG_ADDR 0xF4
#define BMP280_CONFIG_REG_ADDR 0xF5
#define BMP280_P_MSB_REG_ADDR 0xF7
#define BMP280_P_LSB_REG_ADDR 0xF8
#define BMP280_P_XLSB_REG_ADDR 0xF9
#define BMP280_T_MSB_REG_ADDR 0xFA
#define BMP280_T_LSB_REG_ADDR 0xFB
#define BMP280_T_XLSB_REG_ADDR 0xFC
// BMP280 ID
#define BMP280_ID_NB 0x58
//BMP280 RESET COMMAND VALUE
#define BMP280_RESET_VAL 0xB6
#define BMP280_EOC_BIT (1<<3)
#define BMP280_NVRAM_COPY_BIT (1<<0)
// BMP280 CONTROL MEASUREMENT REGISTER BIT VALUES.
#define BMP280_NO_OVERSAMPLING_T (0x00<<5)
#define BMP280_OVERSAMPLING_1X_T (0x01<<5)
#define BMP280_OVERSAMPLING_2X_T (0x02<<5)
#define BMP280_OVERSAMPLING_4X_T (0x03<<5)
#define BMP280_OVERSAMPLING_8X_T (0x04<<5)
#define BMP280_OVERSAMPLING_16X_T (0x05<<5)
#define BMP280_NO_OVERSAMPLING_P (0x00<<2)
#define BMP280_OVERSAMPLING_1X_P (0x01<<2)
#define BMP280_OVERSAMPLING_2X_P (0x02<<2)
#define BMP280_OVERSAMPLING_4X_P (0x03<<2)
#define BMP280_OVERSAMPLING_8X_P (0x04<<2)
#define BMP280_OVERSAMPLING_16X_P (0x05<<2)
#define BMP280_POWER_SLEEP_MODE (0x00)
#define BMP280_POWER_FORCED_MODE (0x01) // OX02 IS EXACTLY THE SAME
#define BMP280_POWER_NORMAL_MODE (0x03)
// BMP280 CONFIG REGISTER BIT VALUES
#define BMP280_INACTIVITY_HALF_MS (0x00<<5)
#define BMP280_INACTIVITY_62_5_MS (0x01<<5)
#define BMP280_INACTIVITY_125_MS (0x02<<5)
#define BMP280_INACTIVITY_250_MS (0x03<<5)
#define BMP280_INACTIVITY_500_MS (0x04<<5)
#define BMP280_INACTIVITY_1000_MS (0x05<<5)
#define BMP280_INACTIVITY_2000_MS (0x06<<5)
#define BMP280_INACTIVITY_4000_MS (0x07<<5)
#define BMP280_IIR_FILTER_COEFF_1 (0x00<<2)
#define BMP280_IIR_FILTER_COEFF_2 (0x01<<2)
#define BMP280_IIR_FILTER_COEFF_4 (0x02<<2)
#define BMP280_IIR_FILTER_COEFF_8 (0x03<<2)
#define BMP280_IIR_FILTER_COEFF_16 (0x04<<2)
#define BMP280_DISABLE_SPI_IF (0x00) // DEFAULT
#define BMP280_ENABLE_SPI_IF (0x01)
/**\name Power mode macros */
#define BMP280_SLEEP_MODE 0x00
#define BMP280_FORCED_MODE 0x01
#define BMP280_NORMAL_MODE 0x03
/**\name Sensor component selection macros */
#define BMP280_PRESS 0x01
#define BMP280_TEMP 0x02
#define BMP280_ALL 0x03
/**\name Macro to combine two 8 bit data's to form a 16 bit data */
#define BMP280_CONCAT_BYTES(msb, lsb) (((uint16_t)msb << 8) | (uint16_t)lsb)
#ifndef BMP280_COMPENSATION
#define BMP280_COMPENSATION BMP280_DOUBLE_PRECISION_COMPENSATION
#endif
/**
* @brief Status enum
*/
enum Bmp280Status {
BMP280_STATUS_UNINIT,
BMP280_STATUS_GET_CALIB,
BMP280_STATUS_CONFIGURE,
BMP280_STATUS_READ_STATUS_REG,
BMP280_STATUS_READ_DATA_REGS
};
// brief Register Trim Variables
struct bmp280_reg_calib_data {
uint16_t dig_t1;
int16_t dig_t2;
int16_t dig_t3;
uint16_t dig_p1;
int16_t dig_p2;
int16_t dig_p3;
int16_t dig_p4;
int16_t dig_p5;
int16_t dig_p6;
int16_t dig_p7;
int16_t dig_p8;
int16_t dig_p9;
int32_t t_fine;
};
#endif /* BMP280_REGS_H */