mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
Merge branch 'dev'
This commit is contained in:
@@ -206,13 +206,12 @@
|
||||
-->
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
|
||||
<!-- -->
|
||||
<!-- <load name="ins_ppzuavimu.xml" /> -->
|
||||
|
||||
<!--
|
||||
<load name="digital_cam.xml" >
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
</load>
|
||||
<load name="ins_ppzuavimu.xml" />
|
||||
-->
|
||||
</modules>
|
||||
|
||||
@@ -243,13 +242,13 @@
|
||||
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" />
|
||||
</subsystem>
|
||||
<subsystem name="imu" type="aspirin_i2c"/>
|
||||
-->
|
||||
|
||||
-->
|
||||
<subsystem name="imu" type="ppzuav"/>
|
||||
<subsystem name="attitude" type="dcm">
|
||||
<define name="USE_MAGNETOMETER" />
|
||||
<!-- <define name="USE_MAGNETOMETER" /> -->
|
||||
</subsystem>
|
||||
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
|
||||
@@ -142,7 +142,7 @@ main_stm32.srcs += subsystems/imu.c \
|
||||
arch/$(ARCH)/subsystems/imu/imu_crista_arch.c
|
||||
main_stm32.CFLAGS += -DUSE_DMA1_C4_IRQ
|
||||
|
||||
main_stm32.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
main_stm32.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
main_stm32.srcs += firmwares/rotorcraft/actuators/actuators_asctec.c
|
||||
#\
|
||||
# $(SRC_BOOZ_ARCH)/actuators/actuators_asctec_arch.c
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
<!-- commands section -->
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1050" neutral="1050" max="1900"/>
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1850" neutral="1480" max="1100"/> <!-- 400 - 380 -->
|
||||
<servo name="AILEVON_RIGHT" no="1" min="1850" neutral="1480" max="1100"/> <!-- 400 - 380 -->
|
||||
<servo name="AILEVON_LEFT" no="2" min="1250" neutral="1580" max="1980"/> <!-- 300 - 400 -->
|
||||
</servos>
|
||||
|
||||
@@ -28,7 +28,7 @@
|
||||
|
||||
<command_laws>
|
||||
<let var="aileron" value="@ROLL * AILEVON_AILERON_RATE"/>
|
||||
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
|
||||
<let var="elevator" value="@PITCH * AILEVON_ELEVATOR_RATE"/>
|
||||
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
<set servo="AILEVON_LEFT" value="$elevator + $aileron"/>
|
||||
@@ -42,7 +42,7 @@
|
||||
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<!-- MAX1168 ADC CHANNELS -->
|
||||
<!-- MAX1168 ADC CHANNELS -->
|
||||
<define name="GYRO_P_CHAN" value="0"/>
|
||||
<define name="GYRO_Q_CHAN" value="1"/>
|
||||
<define name="GYRO_R_CHAN" value="2"/>
|
||||
@@ -81,9 +81,9 @@
|
||||
<define name="ACCEL_Y_SENS" value="0.9346" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="0.9178" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_SIGN" value="-1"/>
|
||||
<define name="ACCEL_Y_SIGN" value="1"/>
|
||||
<define name="ACCEL_Z_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_NEUTRAL" value="0"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="0"/>
|
||||
@@ -92,7 +92,7 @@
|
||||
<define name="MAG_X_SENS" value="1" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="1" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="1" integer="16"/>
|
||||
|
||||
|
||||
<!-- <define name="MAG_45_HACK" value="1"/> -->
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0"/>
|
||||
@@ -161,7 +161,7 @@
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="-6000."/>
|
||||
<define name="ROLL_RATE_GAIN" value="-600."/>
|
||||
|
||||
<define name="ROLL_SLEW" value="0.02"/> <!-- Maximal roll angle change per 1/60 of second: 0.02 rad/loop * 180/pi * 60 loop/sec = 60 deg/sec -->
|
||||
<define name="ROLL_SLEW" value="0.02"/> <!-- Maximal roll angle change per 1/60 of second: 0.02 rad/loop * 180/pi * 60 loop/sec = 60 deg/sec -->
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
|
||||
@@ -0,0 +1,240 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
YAPA + XSens + XBee
|
||||
-->
|
||||
|
||||
<airframe name="Yapa v1">
|
||||
|
||||
<servos>
|
||||
<servo name="THROTTLE" no="0" min="1100" neutral="1100" max="1900"/>
|
||||
<servo name="AILERON_LEFT" no="2" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="AILERON_RIGHT" no="6" min="900" neutral="1500" max="2100"/>
|
||||
<servo name="ELEVATOR" no="7" min="1900" neutral="1500" max="1100"/>
|
||||
<servo name="RUDDER" no="3" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="THROTTLE" failsafe_value="0"/>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="BRAKE" failsafe_value="9600"/> <!-- both elerons up as butterfly brake ? -->
|
||||
</commands>
|
||||
|
||||
<rc_commands>
|
||||
<set command="THROTTLE" value="@THROTTLE"/>
|
||||
<set command="ROLL" value="@ROLL"/>
|
||||
<set command="YAW" value="@YAW"/>
|
||||
<set command="PITCH" value="@PITCH"/>
|
||||
<set command="BRAKE" value="@FLAPS"/>
|
||||
</rc_commands>
|
||||
|
||||
<section name="SERVO_MIXER_GAINS">
|
||||
<define name="AILERON_NEUTRAL" value="0.3f"/>
|
||||
|
||||
<define name="AILERON_RATE_UP" value="1.0f"/>
|
||||
<define name="AILERON_RATE_DOWN" value="0.5f"/>
|
||||
|
||||
<define name="AILERON_RATE_UP_BRAKE" value="1.0f"/>
|
||||
<define name="AILERON_RATE_DOWN_BRAKE" value="1.0f"/>
|
||||
|
||||
<define name="PITCH_GAIN" value="0.9f"/>
|
||||
|
||||
<define name="BRAKE_AILEVON" value="-0.7f"/>
|
||||
<define name="BRAKE_PITCH" value="0.1f"/>
|
||||
<define name="MAX_BRAKE_RATE" value="130"/>
|
||||
|
||||
<define name="RUDDER_OF_AILERON" value="0.3"/>
|
||||
|
||||
<define name="LIMIT(X,XL,XH)" value="( ((X)>(XH)) ? (XH) : ( ((X)>(XL)) ? (X) : (XL) ) )"/>
|
||||
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<!-- Brake Rate Limiter -->
|
||||
<let var="brake_value_nofilt" value="LIMIT(-@BRAKE, 0, MAX_PPRZ)"/>
|
||||
<let var="test; \
|
||||
static int16_t _var_brake_value = 0; \
|
||||
_var_brake_value += LIMIT(_var_brake_value_nofilt - _var_brake_value,-MAX_BRAKE_RATE,MAX_BRAKE_RATE); \
|
||||
int verwaarloos_deze_warning_CDW" value="0"/>
|
||||
|
||||
<!-- Differential Aileron Depending on Brake Value -->
|
||||
<let var="aileron_up_rate" value="(AILERON_RATE_UP * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_UP_BRAKE * $brake_value)"/>
|
||||
<let var="aileron_down_rate" value="(AILERON_RATE_DOWN * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_DOWN_BRAKE * $brake_value)"/>
|
||||
<let var="aileron_up" value="(@ROLL * (((float)$aileron_up_rate) / ((float)MAX_PPRZ)))"/>
|
||||
<let var="aileron_down" value="(@ROLL * (((float)$aileron_down_rate) / ((float)MAX_PPRZ)))"/>
|
||||
<let var="leftturn" value="(@ROLL >= 0? 1 : 0)"/>
|
||||
<let var="rightturn" value="(1 - $leftturn)"/>
|
||||
<set servo="AILERON_LEFT" value="($aileron_up * $leftturn) + ($aileron_down * $rightturn) - $brake_value*(BRAKE_AILEVON) - (MAX_PPRZ * AILERON_NEUTRAL)"/>
|
||||
<set servo="AILERON_RIGHT" value="($aileron_up * $rightturn) + ($aileron_down * $leftturn) + $brake_value*(BRAKE_AILEVON) + (MAX_PPRZ *AILERON_NEUTRAL)"/>
|
||||
|
||||
<set servo="RUDDER" value="@YAW + @ROLL * RUDDER_OF_AILERON"/>
|
||||
<set servo="THROTTLE" value="@THROTTLE"/>
|
||||
|
||||
<!-- Pitch with Brake-Trim Function -->
|
||||
<set servo="ELEVATOR" value="@PITCH * PITCH_GAIN - BRAKE_PITCH * $brake_value"/>
|
||||
</command_laws>
|
||||
|
||||
<!-- Local magnetic field -->
|
||||
<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" />
|
||||
</section>
|
||||
|
||||
<section name="XSENS">
|
||||
<define name="GPS_IMU_LEVER_ARM_X" value="-0.285f" />
|
||||
<define name="GPS_IMU_LEVER_ARM_Y" value="0.0f" />
|
||||
<define name="GPS_IMU_LEVER_ARM_Z" value="0.0f" />
|
||||
</section>
|
||||
|
||||
<section name="AUTO1" prefix="AUTO1_">
|
||||
<define name="MAX_ROLL" value="RadOfDeg(75)"/>
|
||||
<define name="MAX_PITCH" value="RadOfDeg(45)"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<!-- <define name="MilliAmpereOfAdc(adc)" value="((adc) - 505) * 124.0f"/> -->
|
||||
|
||||
<define name="LOW_BAT_LEVEL" value="10.5" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="10" unit="V"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="14." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
<define name="CONTROL_RATE" value="60" unit="Hz"/>
|
||||
<define name="XBEE_INIT" value=""ATPL2\rATRN5\rATTT80\r""/>
|
||||
<!-- <define name="NO_XBEE_API_INIT" value="TRUE"/> -->
|
||||
<!-- <define name="ALT_KALMAN_ENABLED" value="TRUE"/> -->
|
||||
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="80."/>
|
||||
|
||||
<define name="GLIDE_AIRSPEED" value="10"/>
|
||||
<define name="GLIDE_VSPEED" value="3."/>
|
||||
<define name="GLIDE_PITCH" value="45" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="VERTICAL CONTROL" prefix="V_CTL_">
|
||||
<define name="POWER_CTL_BAT_NOMINAL" value="11.1" unit="volt"/>
|
||||
<!-- outer loop proportional gain -->
|
||||
<define name="ALTITUDE_PGAIN" value="-0.108000002801"/>
|
||||
<!-- outer loop saturation -->
|
||||
<define name="ALTITUDE_MAX_CLIMB" value="2."/>
|
||||
|
||||
<!-- auto throttle inner loop -->
|
||||
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.57800000906"/>
|
||||
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
|
||||
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.65"/>
|
||||
<define name="AUTO_THROTTLE_LOITER_TRIM" value="1500"/>
|
||||
<define name="AUTO_THROTTLE_DASH_TRIM" value="-4000"/>
|
||||
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.108999997377" unit="%/(m/s)"/>
|
||||
<define name="AUTO_THROTTLE_PGAIN" value="0."/>
|
||||
<define name="AUTO_THROTTLE_IGAIN" value="0."/>
|
||||
<define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.324999988079"/>
|
||||
|
||||
<define name="THROTTLE_SLEW_LIMITER" value="2" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="HORIZONTAL CONTROL" prefix="H_CTL_">
|
||||
<define name="COURSE_PGAIN" value="-1.20000004768"/>
|
||||
<define name="COURSE_DGAIN" value="0.300000011921"/>
|
||||
<define name="COURSE_PRE_BANK_CORRECTION" value="1.01600003242"/>
|
||||
|
||||
<define name="ROLL_MAX_SETPOINT" value="0.851999998093" unit="radians"/>
|
||||
<define name="PITCH_MAX_SETPOINT" value="0.5" unit="radians"/>
|
||||
<define name="PITCH_MIN_SETPOINT" value="-0.5" unit="radians"/>
|
||||
|
||||
<define name="PITCH_PGAIN" value="-13476.5615234"/>
|
||||
<define name="PITCH_DGAIN" value="7.73400020599"/>
|
||||
|
||||
<define name="ELEVATOR_OF_ROLL" value="3007.81298828"/>
|
||||
|
||||
<define name="ROLL_SLEW" value="1."/>
|
||||
|
||||
<define name="ROLL_ATTITUDE_GAIN" value="-11718.75"/>
|
||||
<define name="ROLL_RATE_GAIN" value="-820.312011719"/>
|
||||
</section>
|
||||
|
||||
<section name="AGGRESSIVE" prefix="AGR_">
|
||||
<define name="BLEND_START" value="30"/>
|
||||
<define name="BLEND_END" value="15"/>
|
||||
<define name="CLIMB_THROTTLE" value="1.00"/>
|
||||
<define name="CLIMB_PITCH" value="RadOfDeg(30)"/>
|
||||
<define name="DESCENT_THROTTLE" value="0.0"/>
|
||||
<define name="DESCENT_PITCH" value="RadOfDeg(-15)"/>
|
||||
<define name="CLIMB_NAV_RATIO" value="0.8"/>
|
||||
<define name="DESCENT_NAV_RATIO" value="1.0"/>
|
||||
</section>
|
||||
|
||||
<section name="FAILSAFE" prefix="FAILSAFE_">
|
||||
<define name="DEFAULT_THROTTLE" value="0.35" unit="%"/>
|
||||
<define name="DEFAULT_ROLL" value="0.17" unit="rad"/>
|
||||
<define name="DEFAULT_PITCH" value="0.08" unit="rad"/>
|
||||
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="(MAX_DIST_FROM_HOME*1.5)"/>
|
||||
<define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
|
||||
</section>
|
||||
|
||||
<section name="DIGITAL_CAMERA" prefix="DC_">
|
||||
<define name="AUTOSHOOT_QUARTERSEC_PERIOD" value="6" unit="quarter_second"/>
|
||||
<define name="AUTOSHOOT_METER_GRID" value="50" unit="meter"/>
|
||||
</section>
|
||||
|
||||
|
||||
<modules>
|
||||
<load name="ins_xsens_MTiG_fixedwing.xml">
|
||||
<configure name="XSENS_UART_NR" value="0"/>
|
||||
</load>
|
||||
|
||||
<load name="light.xml">
|
||||
<define name="LIGHT_LED_STROBE" value="3"/>
|
||||
<define name="LIGHT_LED_NAV" value="2"/>
|
||||
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
|
||||
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
|
||||
</load>
|
||||
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
<!-- <load name="ins_ppzuavimu.xml"/> -->
|
||||
<load name="digital_cam.xml">
|
||||
<define name="DC_SHUTTER_LED" value="2"/>
|
||||
</load>
|
||||
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
|
||||
<target name="ap" board="tiny_2.11">
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
<define name="WIND_INFO_RET"/>
|
||||
<define name="LOITER_TRIM"/>
|
||||
</target>
|
||||
<target name="sim" board="pc"/>
|
||||
|
||||
<subsystem name="radio_control" type="ppm"/>
|
||||
|
||||
<!-- Communication -->
|
||||
<subsystem name="telemetry" type="xbee_api">
|
||||
<configure name="MODEM_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
|
||||
<!-- Actuators -->
|
||||
<subsystem name="control"/>
|
||||
<!-- Sensors -->
|
||||
<subsystem name="navigation"/>
|
||||
<subsystem name="gps" type="xsens"/>
|
||||
|
||||
<subsystem name="i2c"/>
|
||||
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
@@ -1,6 +1,6 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!--
|
||||
<!--
|
||||
YAPA + XSens + XBee
|
||||
-->
|
||||
|
||||
@@ -42,16 +42,21 @@
|
||||
<define name="BRAKE_PITCH" value="0.0f"/>
|
||||
<define name="MAX_BRAKE_RATE" value="150"/>
|
||||
|
||||
<define name="LIMIT(X,XL,XH)" value="( ((X)>(XH)) ? (XH) : ( ((X)>(XL)) ? (X) : (XL) ) )"/>
|
||||
</section>
|
||||
<define name="RATELIMIT(X,RATE)" value="( _rate_limited_value + Chop( (X) - _rate_limited_value, -(RATE), (RATE) )); \
|
||||
int16_t _rate_limited_value = 0;"/>
|
||||
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<!-- Brake Rate Limiter -->
|
||||
<let var="brake_value_nofilt" value="LIMIT(-@BRAKE, 0, MAX_PPRZ)"/>
|
||||
<let var="brake_value" value="Chop(-@BRAKE, 0, MAX_PPRZ)"/>
|
||||
<!--<let var="brake_value" value="RATELIMIT( $brake_value , MAX_BRAKE_RATE )"/>
|
||||
|
||||
<let var="test; \
|
||||
static int16_t _var_brake_value = 0; \
|
||||
_var_brake_value += LIMIT(_var_brake_value_nofilt - _var_brake_value,-MAX_BRAKE_RATE,MAX_BRAKE_RATE); \
|
||||
int verwaarloos_deze_warning_CDW" value="0"/>
|
||||
-->
|
||||
|
||||
<!-- Differential Aileron Depending on Brake Value -->
|
||||
<let var="aileron_up_rate" value="(AILERON_RATE_UP * (MAX_PPRZ - $brake_value)) + (AILERON_RATE_UP_BRAKE * $brake_value)"/>
|
||||
@@ -83,6 +88,11 @@
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.1" unit="V"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
<define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="MISC">
|
||||
<define name="NOMINAL_AIRSPEED" value="13." unit="m/s"/>
|
||||
<define name="CARROT" value="5." unit="s"/>
|
||||
@@ -177,14 +187,17 @@
|
||||
<define name="STROBE_LIGHT_MODE_DEFAULT" value="6"/>
|
||||
<define name="NAV_LIGHT_MODE_DEFAULT" value="4"/>
|
||||
</load>
|
||||
|
||||
<!-- <load name="digital_cam_i2c.xml"/> -->
|
||||
<!-- <load name="ins_ppzuavimu.xml"/> -->
|
||||
<load name="digital_cam.xml" >
|
||||
<define name="DC_SHUTTER_LED" value="3"/>
|
||||
<define name="DC_SHUTTER_LED" value="2"/>
|
||||
</load>
|
||||
|
||||
</modules>
|
||||
|
||||
<firmware name="fixedwing">
|
||||
|
||||
<target name="ap" board="tiny_2.11">
|
||||
<define name="STRONG_WIND"/>
|
||||
<define name="WIND_INFO"/>
|
||||
@@ -204,11 +217,11 @@
|
||||
<!-- Actuators -->
|
||||
<subsystem name="control"/>
|
||||
<!-- Sensors -->
|
||||
<subsystem name="navigation" type="extra"/>
|
||||
<subsystem name="navigation"/>
|
||||
<subsystem name="gps" type="xsens"/>
|
||||
|
||||
<!--<subsystem name="i2c"/>-->
|
||||
<subsystem name="i2c"/>
|
||||
|
||||
</firmware>
|
||||
</firmware>
|
||||
|
||||
</airframe>
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<target name="ap" board="booz_1.0">
|
||||
<!--<define name="KILL_MOTORS"/>--> <!-- prevent motors from ever starting -->
|
||||
<!--<define name="RADIO_KILL_SWITCH" value="RADIO_CONTROL_SWITCH1"/>-->
|
||||
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
</target>
|
||||
|
||||
<target name="sim" board="pc">
|
||||
|
||||
@@ -631,7 +631,7 @@ test_actuators_mkk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
test_actuators_mkk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2
|
||||
test_actuators_mkk.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_actuators_mkk.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
|
||||
test_actuators_mkk.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c1
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
|
||||
@@ -663,7 +663,7 @@ test_actuators_asctecv1.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
test_actuators_asctecv1.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2
|
||||
test_actuators_asctecv1.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_actuators_asctecv1.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
test_actuators_asctecv1.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
test_actuators_asctecv1.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c1
|
||||
test_actuators_asctecv1.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
|
||||
test_actuators_asctecv1.CFLAGS += -DUSE_I2C1
|
||||
@@ -701,6 +701,52 @@ test_bmp085.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_arch.c
|
||||
|
||||
|
||||
|
||||
#
|
||||
# Test manual : a simple test with rc and servos - I want to fly lisa/M
|
||||
#
|
||||
test_manual.ARCHDIR = $(ARCH)
|
||||
test_manual.CFLAGS = -I$(SRC_FIRMWARE) -I$(ARCH) -DPERIPHERALS_AUTO_INIT
|
||||
test_manual.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG)
|
||||
test_manual.srcs = $(SRC_AIRBORNE)/mcu.c \
|
||||
$(SRC_ARCH)/mcu_arch.c \
|
||||
test/test_manual.c \
|
||||
$(SRC_ARCH)/stm32_exceptions.c \
|
||||
$(SRC_ARCH)/stm32_vector_table.c
|
||||
test_manual.CFLAGS += -DUSE_LED
|
||||
test_manual.srcs += $(SRC_ARCH)/led_hw.c
|
||||
test_manual.CFLAGS += -DUSE_SYS_TIME -DSYS_TIME_LED=$(SYS_TIME_LED)
|
||||
test_manual.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)'
|
||||
test_manual.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
|
||||
|
||||
test_manual.CFLAGS += -DUSE_$(MODEM_PORT) -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD)
|
||||
test_manual.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
|
||||
test_manual.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT)
|
||||
test_manual.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_manual.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
|
||||
test_manual.CFLAGS += -I$(SRC_FIRMWARE)/actuators/arch/$(ARCH)
|
||||
#test_manual.srcs += $(SRC_FIRMWARE)/actuators/actuators_pwm.c
|
||||
test_manual.srcs += $(SRC_FIRMWARE)/actuators/arch/$(ARCH)/actuators_pwm_arch.c
|
||||
test_manual.srcs += $(SRC_FIRMWARE)/actuators/actuators_heli.c
|
||||
|
||||
|
||||
test_manual.CFLAGS += -I$(SRC_BOOZ) -I$(SRC_BOOZ)/arch/$(ARCH)
|
||||
test_manual.CFLAGS += -DRADIO_CONTROL
|
||||
ifdef RADIO_CONTROL_LED
|
||||
test_manual.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED)
|
||||
endif
|
||||
test_manual.CFLAGS += -DRADIO_CONTROL_BIND_IMPL_FUNC=radio_control_spektrum_try_bind
|
||||
test_manual.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/spektrum.h\"
|
||||
test_manual.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_PRIMARY_PORT=$(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT)
|
||||
test_manual.CFLAGS += -DOVERRIDE_$(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT)_IRQ_HANDLER -DUSE_TIM6_IRQ
|
||||
test_manual.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \
|
||||
subsystems/radio_control/spektrum.c \
|
||||
$(SRC_ARCH)/subsystems/radio_control/spektrum_arch.c
|
||||
|
||||
|
||||
|
||||
#
|
||||
# tunnel sw
|
||||
#
|
||||
|
||||
@@ -61,7 +61,7 @@ stm_passthrough.srcs += $(SRC_LISA)/lisa_overo_link.c \
|
||||
stm_passthrough.srcs += math/pprz_trig_int.c
|
||||
stm_passthrough.srcs += lisa/plug_sys.c
|
||||
|
||||
stm_passthrough.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
stm_passthrough.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
|
||||
# Radio control
|
||||
#
|
||||
|
||||
@@ -197,7 +197,7 @@ test_actuators_mkk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
test_actuators_mkk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=$(MODEM_PORT)
|
||||
test_actuators_mkk.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_actuators_mkk.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
|
||||
test_actuators_mkk.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c0
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
|
||||
|
||||
@@ -607,7 +607,7 @@ test_actuators_mkk.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
test_actuators_mkk.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2
|
||||
test_actuators_mkk.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_actuators_mkk.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
|
||||
test_actuators_mkk.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c1 -DUSE_TIM2_IRQ
|
||||
#test_actuators_mkk.CFLAGS += -DACTUATORS_ASCTEC_V2_PROTOCOL -DACTUATORS_ASCTEC_DEVICE=i2c1
|
||||
@@ -640,7 +640,7 @@ test_actuators_asctec.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
test_actuators_asctec.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart2
|
||||
test_actuators_asctec.srcs += downlink.c pprz_transport.c
|
||||
|
||||
test_actuators_asctec.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
test_actuators_asctec.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
test_actuators_asctec.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
|
||||
test_actuators_asctec.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c1
|
||||
# -DBOOZ_START_DELAY=3
|
||||
@@ -1100,7 +1100,7 @@ ptw.srcs += peripherals/max1168.c $(SRC_ARCH)/peripherals/max1168_arch.c
|
||||
ptw.srcs += peripherals/ms2100.c $(SRC_ARCH)/peripherals/ms2100_arch.c
|
||||
ptw.srcs += math/pprz_trig_int.c
|
||||
|
||||
ptw.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
ptw.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
|
||||
# Radio control
|
||||
ptw.CFLAGS += -DRADIO_CONTROL
|
||||
|
||||
@@ -101,7 +101,7 @@ ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
|
||||
ap.srcs += mcu_periph/i2c.c
|
||||
ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c
|
||||
|
||||
ap.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
ap.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
|
||||
#
|
||||
# Radio control choice
|
||||
@@ -216,7 +216,7 @@ ap.srcs += $(SRC_SUBSYSTEMS)/ins/vf_float.c
|
||||
ap.CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./$(PERIODIC_FREQUENCY).)'
|
||||
|
||||
ap.srcs += $(SRC_FIRMWARE)/navigation.c
|
||||
|
||||
ap.srcs += subsystems/navigation/common_flight_plan.c
|
||||
|
||||
#
|
||||
# FMS choice
|
||||
|
||||
@@ -81,6 +81,11 @@ $(TARGET).srcs += sys_time.c
|
||||
$(TARGET).CFLAGS += -DINTER_MCU
|
||||
$(TARGET).srcs += $(SRC_FIXEDWING)/inter_mcu.c
|
||||
|
||||
#
|
||||
# Math functions
|
||||
#
|
||||
$(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_geodetic_double.c
|
||||
|
||||
######################################################################
|
||||
##
|
||||
## COMMON FOR ALL NON-SIMULATION TARGETS
|
||||
|
||||
@@ -10,7 +10,13 @@ ifneq ($(GPS_LED),none)
|
||||
ap.CFLAGS += -DGPS_LED=$(GPS_LED)
|
||||
endif
|
||||
|
||||
ap.srcs += $(SRC_FIXEDWING)/gps_ubx.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c
|
||||
|
||||
$(TARGET).srcs += $(SRC_FIXEDWING)/gps.c $(SRC_FIXEDWING)/latlong.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
|
||||
sim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
|
||||
|
||||
jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
|
||||
jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
|
||||
|
||||
@@ -10,6 +10,14 @@ ifneq ($(GPS_LED),none)
|
||||
ap.CFLAGS += -DGPS_LED=$(GPS_LED)
|
||||
endif
|
||||
|
||||
ap.srcs += $(SRC_FIXEDWING)/gps_ubx.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c
|
||||
|
||||
$(TARGET).srcs += $(SRC_FIXEDWING)/gps.c $(SRC_FIXEDWING)/latlong.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
|
||||
sim.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG
|
||||
sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
|
||||
|
||||
jsbsim.CFLAGS += -DUSE_GPS -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
|
||||
jsbsim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
|
||||
|
||||
@@ -2,5 +2,5 @@
|
||||
|
||||
|
||||
ap.CFLAGS += -DUSE_GPS -DUBX -DGPS_USE_LATLONG
|
||||
|
||||
ap.srcs += $(SRC_FIXEDWING)/gps_ubx.c $(SRC_FIXEDWING)/gps.c $(SRC_FIXEDWING)/latlong.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c $(SRC_SUBSYSTEMS)/gps.c
|
||||
|
||||
@@ -3,6 +3,5 @@
|
||||
|
||||
# ap.CFLAGS += -DGPS
|
||||
|
||||
ap.srcs += $(SRC_FIXEDWING)/gps_xsens.c $(SRC_FIXEDWING)/gps.c $(SRC_FIXEDWING)/latlong.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
|
||||
sim.srcs += $(SRC_FIXEDWING)/gps.c $(SRC_FIXEDWING)/latlong.c
|
||||
|
||||
@@ -52,7 +52,6 @@ imu_srcs += $(SRC_ARCH)/peripherals/max1168_arch.c
|
||||
#ifeq ($(ARCH), lpc21)
|
||||
imu_CFLAGS += -DSSP_VIC_SLOT=9
|
||||
imu_CFLAGS += -DMAX1168_EOC_VIC_SLOT=8
|
||||
#FIXME ms2100 not used on this imu
|
||||
#else ifeq ($(ARCH), stm32)
|
||||
#imu_CFLAGS += -DUSE_SPI2 -DUSE_DMA1_C4_IRQ -DUSE_EXTI2_IRQ -DUSE_SPI2_IRQ
|
||||
#imu_CFLAGS += -DMAX_1168_DRDY_PORT=$(MAX_1168_DRDY_PORT)
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
|
||||
$(TARGET).CFLAGS += -DNAV
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/nav.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/common_flight_plan.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/traffic_info.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/nav_survey_rectangle.c $(SRC_SUBSYSTEMS)/navigation/nav_line.c
|
||||
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
|
||||
$(TARGET).CFLAGS += -DNAV
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/nav.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/common_flight_plan.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/traffic_info.c
|
||||
$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/nav_survey_rectangle.c $(SRC_SUBSYSTEMS)/navigation/nav_line.c
|
||||
|
||||
|
||||
@@ -82,7 +82,7 @@ sim.srcs += $(SRC_FIRMWARE)/telemetry.c \
|
||||
downlink.c \
|
||||
$(SRC_ARCH)/ivy_transport.c
|
||||
|
||||
sim.srcs += $(SRC_BOOZ)/booz2_commands.c
|
||||
sim.srcs += $(SRC_FIRMWARE)/commands.c
|
||||
|
||||
sim.srcs += $(SRC_FIRMWARE)/datalink.c
|
||||
|
||||
@@ -169,3 +169,4 @@ sim.CFLAGS += -DUSE_VFF -DDT_VFILTER='(1./512.)'
|
||||
|
||||
|
||||
sim.srcs += $(SRC_FIRMWARE)/navigation.c
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/navigation/common_flight_plan.c
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
|
||||
ap.srcs += $(SRC_BOOZ)/booz_gps.c
|
||||
ap.CFLAGS += -DBOOZ_GPS_TYPE_H=\"gps/booz_gps_skytraq.h\"
|
||||
ap.srcs += $(SRC_BOOZ)/gps/booz_gps_skytraq.c
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_skytraq.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_skytraq.c
|
||||
|
||||
ap.CFLAGS += -DUSE_$(GPS_PORT) -D$(GPS_PORT)_BAUD=$(GPS_BAUD)
|
||||
ap.CFLAGS += -DUSE_GPS -DGPS_LINK=$(GPS_PORT)
|
||||
@@ -11,4 +11,4 @@ ifneq ($(GPS_LED),none)
|
||||
endif
|
||||
|
||||
sim.CFLAGS += -DUSE_GPS
|
||||
sim.srcs += $(SRC_BOOZ)/booz_gps.c
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
|
||||
ap.srcs += $(SRC_BOOZ)/booz_gps.c
|
||||
ap.CFLAGS += -DBOOZ_GPS_TYPE_H=\"gps/booz_gps_ubx.h\"
|
||||
ap.srcs += $(SRC_BOOZ)/gps/booz_gps_ubx.c
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
ap.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_ubx.h\"
|
||||
ap.srcs += $(SRC_SUBSYSTEMS)/gps/gps_ubx.c
|
||||
|
||||
ap.CFLAGS += -DUSE_$(GPS_PORT) -D$(GPS_PORT)_BAUD=$(GPS_BAUD)
|
||||
ap.CFLAGS += -DUSE_GPS -DGPS_LINK=$(GPS_PORT)
|
||||
@@ -11,4 +11,6 @@ ifneq ($(GPS_LED),none)
|
||||
endif
|
||||
|
||||
sim.CFLAGS += -DUSE_GPS
|
||||
sim.srcs += $(SRC_BOOZ)/booz_gps.c
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/gps.c
|
||||
sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\"
|
||||
sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim_nps.c
|
||||
|
||||
@@ -10,9 +10,10 @@ ifdef AHRS_ALIGNER_LED
|
||||
AHRS_CFLAGS += -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED)
|
||||
endif
|
||||
AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_int_cmpl.h\"
|
||||
AHRS_SRCS += subsystems/ahrs.c
|
||||
AHRS_SRCS += subsystems/ahrs/ahrs_int_cmpl.c
|
||||
AHRS_SRCS += subsystems/ahrs/ahrs_aligner.c
|
||||
AHRS_SRCS += subsystems/ahrs.c
|
||||
AHRS_SRCS += subsystems/ahrs/ahrs_int_cmpl.c
|
||||
AHRS_SRCS += subsystems/ahrs/ahrs_aligner.c
|
||||
AHRS_SRCS += math/pprz_trig_int.c
|
||||
|
||||
ap.CFLAGS += $(AHRS_CFLAGS)
|
||||
ap.srcs += $(AHRS_SRCS)
|
||||
@@ -20,3 +21,23 @@ ap.srcs += $(AHRS_SRCS)
|
||||
sim.CFLAGS += $(AHRS_CFLAGS)
|
||||
sim.srcs += $(AHRS_SRCS)
|
||||
|
||||
|
||||
# Extra stuff for fixedwings
|
||||
|
||||
ifdef CPU_LED
|
||||
ap.CFLAGS += -DAHRS_CPU_LED=$(CPU_LED)
|
||||
endif
|
||||
|
||||
ifdef AHRS_PROPAGATE_FREQUENCY
|
||||
else
|
||||
AHRS_PROPAGATE_FREQUENCY = 60
|
||||
endif
|
||||
|
||||
ifdef AHRS_CORRECT_FREQUENCY
|
||||
else
|
||||
AHRS_CORRECT_FREQUENCY = 60
|
||||
endif
|
||||
|
||||
ap.CFLAGS += -DAHRS_PROPAGATE_FREQUENCY=$(AHRS_PROPAGATE_FREQUENCY)
|
||||
ap.CFLAGS += -DAHRS_CORRECT_FREQUENCY=$(AHRS_CORRECT_FREQUENCY)
|
||||
|
||||
|
||||
+61
-37
@@ -19,15 +19,7 @@
|
||||
<field name="cpu_time" type="uint16" unit="s"></field>
|
||||
</message>
|
||||
|
||||
<!-- add the following msg for debugging Haiyang 20080521-->
|
||||
<message name="DebugChao" id="5">
|
||||
<field name="int16_1" type="int16" unit="deg"></field>
|
||||
<field name="int16_2" type="int16" unit="deg"></field>
|
||||
<field name="int16_3" type="int16" unit="deg"></field>
|
||||
<field name="int32_1" type="int32" unit="deg"></field>
|
||||
<field name="int32_2" type="int32" unit="deg"></field>
|
||||
<field name="int32_3" type="int32" unit="deg"></field>
|
||||
</message>
|
||||
<!-- 5 is free -->
|
||||
|
||||
<message name="ATTITUDE" id="6">
|
||||
<field name="phi" type="float" unit="rad" alt_unit="deg"/>
|
||||
@@ -48,10 +40,10 @@
|
||||
<field name="utm_east" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="utm_north" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="course" type="int16" unit="decideg" alt_unit="deg"/>
|
||||
<field name="alt" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="alt" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="speed" type="uint16" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="climb" type="int16" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="week" type="uint16" unit="weeks"></field>
|
||||
<field name="week" type="uint16" unit="weeks"/>
|
||||
<field name="itow" type="uint32" unit="ms"/>
|
||||
<field name="utm_zone" type="uint8"/>
|
||||
<field name="gps_nb_err" type="uint8"/>
|
||||
@@ -442,7 +434,7 @@
|
||||
<message name="GPS_LLA" id="59">
|
||||
<field name="lat" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="lon" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="alt" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="alt" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="course" type="int16" unit="decideg" alt_unit="deg"/>
|
||||
<field name="speed" type="uint16" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="climb" type="int16" unit="cm/s" alt_unit="m/s"/>
|
||||
@@ -753,16 +745,40 @@
|
||||
<field name="one" type="float"/>
|
||||
</message>
|
||||
|
||||
<!--113 is free -->
|
||||
<message name="MLX_SERIAL" id="113">
|
||||
<field name="serial0" type="uint32"/>
|
||||
<field name="serial1" type="uint32"/>
|
||||
</message>
|
||||
|
||||
<message name="PAYLOAD" id="114">
|
||||
<field name="values" type="uint8[]" unit="none"/>
|
||||
</message>
|
||||
|
||||
<message name="HTM_STATUS" id="115">
|
||||
<field name="ihumid" type="uint16"/>
|
||||
<field name="itemp" type="uint16"/>
|
||||
<field name="humid" type="float" unit="rel_hum" format="%.2f"/>
|
||||
<field name="temp" type="float" unit="deg_celsius" format="%.2f"/>
|
||||
</message>
|
||||
|
||||
<message name="BARO_MS5611" id="116">
|
||||
<field name="d1" type="uint32"/>
|
||||
<field name="d2" type="uint32"/>
|
||||
<field name="pressure" type="float" unit="hPa" format="%.2f"/>
|
||||
<field name="temp" type="float" unit="deg_celsius" format="%.2f"/>
|
||||
</message>
|
||||
|
||||
<message name="MS5611_COEFF" id="117">
|
||||
<field name="c0" type="uint16"/>
|
||||
<field name="c1" type="uint16"/>
|
||||
<field name="c2" type="uint16"/>
|
||||
<field name="c3" type="uint16"/>
|
||||
<field name="c4" type="uint16"/>
|
||||
<field name="c5" type="uint16"/>
|
||||
<field name="c6" type="uint16"/>
|
||||
<field name="c7" type="uint16"/>
|
||||
</message>
|
||||
|
||||
<!--115 is free -->
|
||||
<!--116 is free -->
|
||||
<!--117 is free -->
|
||||
<!--118 is free -->
|
||||
<!--119 is free -->
|
||||
|
||||
@@ -1045,7 +1061,7 @@
|
||||
</message>
|
||||
|
||||
|
||||
<message name="BOOZ2_FP" id="147">
|
||||
<message name="ROTORCRAFT_FP" id="147">
|
||||
<field name="east" type="int32" alt_unit="m" alt_unit_coef="0.0039063"/>
|
||||
<field name="north" type="int32" alt_unit="m" alt_unit_coef="0.0039063"/>
|
||||
<field name="up" type="int32" alt_unit="m" alt_unit_coef="0.0039063"/>
|
||||
@@ -1108,25 +1124,26 @@
|
||||
<field name="ecef_x0" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_y0" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_z0" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="lat0" type="int32" alt_unit="deg" alt_unit_coef="0.0000001"/>
|
||||
<field name="lon0" type="int32" alt_unit="deg" alt_unit_coef="0.0000001"/>
|
||||
<field name="alt0" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="hmsl0" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="lat0" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="lon0" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="alt0" type="int32" alt_unit="m" alt_unit_coef="0.001"/>
|
||||
<field name="hmsl0" type="int32" alt_unit="m" alt_unit_coef="0.001"/>
|
||||
<field name="baro_qfe" type="int32"/>
|
||||
</message>
|
||||
|
||||
<message name="BOOZ2_GPS" id="155">
|
||||
<field name="ecef_x" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_y" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_z" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="lat" type="int32" alt_unit="deg" alt_unit_coef="0.0000001"/>
|
||||
<field name="lon" type="int32" alt_unit="deg" alt_unit_coef="0.0000001"/>
|
||||
<field name="alt" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_xd" type="int32" alt_unit="m/s" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_yd" type="int32" alt_unit="m/s" alt_unit_coef="0.01"/>
|
||||
<field name="ecef_zd" type="int32" alt_unit="m/s" alt_unit_coef="0.01"/>
|
||||
<field name="pacc" type="int32" alt_unit="m" alt_unit_coef="0.01"/>
|
||||
<field name="sacc" type="int32" alt_unit="m/s" alt_unit_coef="0.01"/>
|
||||
<message name="GPS_INT" id="155">
|
||||
<field name="ecef_x" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="ecef_y" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="ecef_z" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="lat" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="lon" type="int32" alt_unit="deg" alt_unit_coef="0.0000057296"/>
|
||||
<field name="alt" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="hmsl" type="int32" unit="mm" alt_unit="m"/>
|
||||
<field name="ecef_xd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="ecef_yd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="ecef_zd" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="pacc" type="int32" unit="cm" alt_unit="m"/>
|
||||
<field name="sacc" type="int32" unit="cm/s" alt_unit="m/s"/>
|
||||
<field name="tow" type="uint32"/>
|
||||
<field name="pdop" type="uint16"/>
|
||||
<field name="numsv" type="uint8"/>
|
||||
@@ -1574,7 +1591,14 @@
|
||||
<field name="mz" type="int32" unit="adc"/>
|
||||
</message>
|
||||
|
||||
<!--206 is free -->
|
||||
<message name="IMU_MAG_SETTINGS" id="206">
|
||||
<field name="inclination" type="float" />
|
||||
<field name="declination" type="float" />
|
||||
<field name="hardiron_x" type="float" />
|
||||
<field name="hardiron_y" type="float" />
|
||||
<field name="hardiron_z" type="float" />
|
||||
</message>
|
||||
|
||||
<!--207 is free -->
|
||||
<!--208 is free -->
|
||||
|
||||
@@ -1862,9 +1886,9 @@
|
||||
<message name="MOVE_WP" id="2" link="forwarded">
|
||||
<field name="wp_id" type="uint8"/>
|
||||
<field name="ac_id" type="uint8"/>
|
||||
<field name="lat" type="int32" unit="e-7deg"></field>
|
||||
<field name="lon" type="int32" unit="e-7deg"></field>
|
||||
<field name="alt" type="int32" unit="cm"></field>
|
||||
<field name="lat" type="int32" unit="e-7deg"/>
|
||||
<field name="lon" type="int32" unit="e-7deg"/>
|
||||
<field name="alt" type="int32" unit="cm"/>
|
||||
</message>
|
||||
|
||||
<message name="WIND_INFO" id="3" link="forwarded">
|
||||
|
||||
@@ -0,0 +1,21 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<!--
|
||||
Measurement Specialties MS5611-01BA pressure sensor (I2C)
|
||||
@param MS5611_I2C_DEV i2c device (default i2c0)
|
||||
-->
|
||||
|
||||
<module name="baro_ms5611_i2c" dir="sensors">
|
||||
<header>
|
||||
<file name="baro_ms5611_i2c.h"/>
|
||||
</header>
|
||||
<init fun="baro_ms5611_init()"/>
|
||||
<periodic fun="baro_ms5611_periodic()" freq="4" delay="0"/>
|
||||
<periodic fun="baro_ms5611_d1()" freq="4" delay="1"/>
|
||||
<periodic fun="baro_ms5611_d2()" freq="4" delay="2"/>
|
||||
<event fun="baro_ms5611_event()"/>
|
||||
<makefile target="ap">
|
||||
<file name="baro_ms5611_i2c.c"/>
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
@@ -0,0 +1,22 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="gps_ubx" dir="gps">
|
||||
<header>
|
||||
<file name="gps_ubx_uart.h"/>
|
||||
</header>
|
||||
<init fun="gps_init()"/>
|
||||
<event fun="GpsEvent(on_gps_solution)"/>
|
||||
<makefile>
|
||||
<file name="gps.c" dir="subsystems"/>
|
||||
</makefile>
|
||||
<makefile target="ap">
|
||||
<file name="gps_ubx.c" dir="subsystems/gps"/>
|
||||
<define name="GPS_TYPE_H" value="\"subsystems/gps/gps_ubx.h\""/>
|
||||
</makefile>
|
||||
<makefile target="sim|jsbsim">
|
||||
<file name="gps_sim.c" dir="subsystems/gps"/>
|
||||
<define name="GPS_TYPE_H" value="\"subsystems/gps/gps_sim.h\""/>
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
|
||||
@@ -0,0 +1,19 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<!--
|
||||
TronSens HTM-B71 humidity sensor (I2C)
|
||||
@param HTM_I2C_DEV i2c device (default i2c0)
|
||||
-->
|
||||
|
||||
<module name="humid_htm_b71" dir="meteo">
|
||||
<header>
|
||||
<file name="humid_htm_b71.h"/>
|
||||
</header>
|
||||
<init fun="humid_htm_init()"/>
|
||||
<periodic fun="humid_htm_start()" freq="4" delay="10"/>
|
||||
<periodic fun="humid_htm_read()" freq="4" delay="14"/>
|
||||
<event fun="humid_htm_event()"/>
|
||||
<makefile target="ap">
|
||||
<file name="humid_htm_b71.c"/>
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -0,0 +1,25 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="ins_aspirin_via_i2c" dir="ins">
|
||||
<!-- <depend conflict="ins" -->
|
||||
<header>
|
||||
<file name="ins_ppzuavimu.h"/>
|
||||
</header>
|
||||
|
||||
<!-- default imu stuff -->
|
||||
<init fun="imu_impl_init()"/>
|
||||
<periodic fun="imu_periodic()" freq="60"/>
|
||||
<!-- ImuEvent called directly from main_ap -->
|
||||
|
||||
<!-- extras to become a usefull module -->
|
||||
<periodic fun="ppzuavimu_module_downlink_raw()" freq="5"/>
|
||||
<event fun="ppzuavimu_module_event()"/>
|
||||
|
||||
<makefile>
|
||||
<file name="ins_ppzuavimu.c"/>
|
||||
<define name="PPZUAVIMU_I2C_DEVICE" value="i2c0" />
|
||||
<define name="USE_I2C" />
|
||||
<define name="USE_I2C0" />
|
||||
<define name="ASPIRIN_IMU" />
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -10,12 +10,17 @@
|
||||
<periodic fun="ins_periodic_task()" freq="60"/>
|
||||
<event fun="InsEventCheckAndHandle(handle_ins_msg())"/>
|
||||
<makefile>
|
||||
<define name="AHRS_TYPE_H" value="\\\"modules/ins/ins_xsens.h\\\"" />
|
||||
<define name="INS_MODULE_H" value="\\\"modules/ins/ins_xsens.h\\\"" />
|
||||
<define name="USE_UART$(XSENS_UART_NR)"/>
|
||||
<define name="INS_LINK" value="Uart$(XSENS_UART_NR)"/>
|
||||
<define name="UART$(XSENS_UART_NR)_BAUD" value="B115200"/>
|
||||
<define name="UART$(XSENS_UART_NR)_BAUD" value="B230400"/>
|
||||
<define name="USE_GPS_XSENS"/>
|
||||
<define name="USE_GPS_XSENS_RAW_DATA" />
|
||||
<define name="GPS_NB_CHANNELS" value="16" />
|
||||
<define name="XSENS_OUTPUT_MODE" value="0x1836" />
|
||||
<file name="ins_xsens.c"/>
|
||||
<define name="AHRS_TRIGGERED_ATTITUDE_LOOP" />
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
|
||||
@@ -0,0 +1,19 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="sensors">
|
||||
<!-- <depend conflict="ins" -->
|
||||
<header>
|
||||
<file name="mag_hmc5843.h"/>
|
||||
</header>
|
||||
<init fun="hmc5843_module_init()"/>
|
||||
<periodic fun="hmc5843_module_periodic()" freq="60"/>
|
||||
<event fun="hmc5843_module_event()"/>
|
||||
<makefile>
|
||||
<define name="USE_I2C" />
|
||||
<file name="mag_hmc5843.c"/>
|
||||
<file name="../../peripherals/hmc5843.c"/>
|
||||
<define name="HMC5843_I2C_DEVICE" value="i2c0" />
|
||||
<define name="USE_I2C0" />
|
||||
<define name="HMC5843_NO_IRQ" />
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -0,0 +1,54 @@
|
||||
<?xml version="1.0"?>
|
||||
<!-- $Id$
|
||||
--
|
||||
-- (c) 2003 Pascal Brisset, Antoine Drouin
|
||||
--
|
||||
-- This file is part of paparazzi.
|
||||
--
|
||||
-- paparazzi is free software; you can redistribute it and/or modify
|
||||
-- it under the terms of the GNU General Public License as published by
|
||||
-- the Free Software Foundation; either version 2, or (at your option)
|
||||
-- any later version.
|
||||
--
|
||||
-- paparazzi is distributed in the hope that it will be useful,
|
||||
-- but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
-- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
-- GNU General Public License for more details.
|
||||
--
|
||||
-- You should have received a copy of the GNU General Public License
|
||||
-- along with paparazzi; see the file COPYING. If not, write to
|
||||
-- the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
-- Boston, MA 02111-1307, USA.
|
||||
-->
|
||||
|
||||
<!--
|
||||
-- Attributes of root (Radio) tag :
|
||||
-- name: name of RC
|
||||
-- min: min width of a pulse to be considered as a data pulse
|
||||
-- max: max width of a pulse to be considered as a data pulse
|
||||
-- sync: min 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="FASST TX Module" data_min="700" data_max="2300" sync_min="4000" sync_max="15000" pulse_type="NEGATIVE">
|
||||
<channel ctl="A" function="ROLL" min="1100" neutral="1500" max="1900" average="0"/> <!-- right stick left/right -->
|
||||
<channel ctl="B" function="PITCH" min="1100" neutral="1500" max="1900" average="0"/> <!-- left stick up/down -->
|
||||
<channel ctl="C" function="THROTTLE" min="1100" neutral="1100" max="1900" average="0"/> <!-- right stick up/down -->
|
||||
<channel ctl="D" function="YAW" min="1900" neutral="1500" max="1100" average="0"/> <!-- left stick left/right-->
|
||||
<channel ctl="E" function="MODE" min="1100" neutral="1500" max="1900" average="0"/> <!-- left switch -->
|
||||
<channel ctl="F" function="EXTRA1" min="1100" neutral="1500" max="1900" average="0"/> <!-- left switch -->
|
||||
<channel ctl="G" function="FLAPS" min="1100" neutral="1500" max="1900" average="0"/> <!-- left switch -->
|
||||
</radio>
|
||||
@@ -25,7 +25,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle">
|
||||
</dl_setting>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="Infrared">
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle">
|
||||
</dl_setting>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
</dl_settings>
|
||||
|
||||
</dl_settings>
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle">
|
||||
</dl_setting>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Ap" shortname="tele_AP"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="control">
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="telemetry_mode_Ap_DefaultChannel" shortname="tele_AP" module="downlink"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Fbw_DefaultChannel" shortname="tele_FBW" module="downlink"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
|
||||
<dl_setting MAX="200" MIN="-200" STEP="10" VAR="nav_radius" module="subsystems/nav" handler="SetNavRadius">
|
||||
<strip_button icon="circle-right.png" name="Circle right" value="1"/>
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle">
|
||||
</dl_setting>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="telemetry_mode_Ap" shortname="tele_AP"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps.reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="control">
|
||||
|
||||
@@ -17,7 +17,7 @@
|
||||
</dl_setting>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle">
|
||||
</dl_setting>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="gps_ubx" handler="Reset" shortname="GPS reset"/>
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="gps_reset" module="subsystems/gps" handler="Reset" shortname="GPS reset"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
<mode name="default">
|
||||
<message name="DL_VALUE" period="2.1"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.4"/>
|
||||
<message name="BOOZ2_FP" period="1.2"/>
|
||||
<message name="ROTORCRAFT_FP" period="1.2"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="INS_REF" period="10.1"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="2.6"/>
|
||||
@@ -18,7 +18,7 @@
|
||||
<mode name="alternate">
|
||||
<message name="DL_VALUE" period="1.1"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="BOOZ2_FP" period="0.25"/>
|
||||
<message name="ROTORCRAFT_FP" period="0.25"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
|
||||
|
||||
@@ -8,13 +8,13 @@
|
||||
<mode name="default">
|
||||
<message name="DL_VALUE" period="1.1"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="BOOZ2_FP" period="0.25"/>
|
||||
<message name="ROTORCRAFT_FP" period="0.25"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
<message name="INS_REF" period="5.1"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
|
||||
<message name="WP_MOVED" period="1.3"/>
|
||||
<message name="BOOZ2_CAM" period="1."/>
|
||||
<message name="BOOZ2_GPS" period=".25"/>
|
||||
<message name="GPS_INT" period=".25"/>
|
||||
<message name="INS" period=".25"/>
|
||||
</mode>
|
||||
|
||||
@@ -88,7 +88,7 @@
|
||||
<message name="STAB_ATTITUDE" period=".4"/>
|
||||
<message name="HFF_DBG" period=".2"/>
|
||||
<!--<message name="STAB_ATTITUDE_REF" period=".4"/>-->
|
||||
<message name="BOOZ2_FP" period="0.8"/>
|
||||
<message name="ROTORCRAFT_FP" period="0.8"/>
|
||||
<message name="ROTORCRAFT_STATUS" period="1.2"/>
|
||||
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
|
||||
<message name="HFF_GPS" period=".03"/>
|
||||
|
||||
@@ -40,6 +40,11 @@
|
||||
</message>
|
||||
<message name="SetBaudrateAck" ID="0x19" to="host"/>
|
||||
|
||||
<message name="SetSyncOutSettings" ID="0xD8" to="MT" length="3">
|
||||
<field name="param" format="U1"/>
|
||||
<field name="value" format="U2"/>
|
||||
</message>
|
||||
|
||||
<message name="RestoreFactoryDef" ID="0x0E" to="MT"/>
|
||||
<message name="RestoreFactoryDefAck" ID="0x0F" to="host"/>
|
||||
|
||||
@@ -118,6 +123,18 @@
|
||||
</message>
|
||||
<message name="SetMagneticDeclinationAck" ID="0x6B" to="host"/>
|
||||
|
||||
<message name="ReqLeverArmGps" ID="0x68" to="MT"/>
|
||||
<message name="SetLeverArmGps" ID="0x68" to="MT" length="12">
|
||||
<field name="x" format="R4" unit="m"/>
|
||||
<field name="y" format="R4" unit="m"/>
|
||||
<field name="z" format="R4" unit="m"/>
|
||||
</message>
|
||||
<message name="ReqLeverArmGpsAck" ID="0x69" to="host" length="12">
|
||||
<field name="x" format="R4" unit="m"/>
|
||||
<field name="y" format="R4" unit="m"/>
|
||||
<field name="z" format="R4" unit="m"/>
|
||||
</message>
|
||||
|
||||
<message name="ReqGPSStatus" ID="0xA6" to="MT"/>
|
||||
<message name="GPSStatus" ID="0xA7" to="host">
|
||||
<field name="nch" format="U1"/>
|
||||
|
||||
+36
-22
@@ -139,24 +139,34 @@
|
||||
#define PERIODIC_SEND_SEGMENT(_chan) if (nav_in_segment) { DOWNLINK_SEND_SEGMENT(_chan, &nav_segment_x_1, &nav_segment_y_1, &nav_segment_x_2, &nav_segment_y_2); }
|
||||
|
||||
#ifdef IMU_TYPE_H
|
||||
#include "subsystems/imu.h"
|
||||
#define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) { DOWNLINK_SEND_IMU_ACCEL_RAW(_chan, &imu.accel_unscaled.x, &imu.accel_unscaled.y, &imu.accel_unscaled.z)}
|
||||
#define PERIODIC_SEND_IMU_GYRO_RAW(_chan) { DOWNLINK_SEND_IMU_GYRO_RAW(_chan, &imu.gyro_unscaled.p, &imu.gyro_unscaled.q, &imu.gyro_unscaled.r)}
|
||||
#define PERIODIC_SEND_IMU_MAG_RAW(_chan) { DOWNLINK_SEND_IMU_MAG_RAW(_chan, &imu.mag_unscaled.x, &imu.mag_unscaled.y, &imu.mag_unscaled.z)}
|
||||
#define PERIODIC_SEND_IMU_ACCEL(_chan) { struct FloatVect3 accel_float; ACCELS_FLOAT_OF_BFP(accel_float, imu.accel); DOWNLINK_SEND_IMU_ACCEL(_chan, &accel_float.x, &accel_float.y, &accel_float.z)}
|
||||
#define PERIODIC_SEND_IMU_GYRO(_chan) { struct FloatRates gyro_float; RATES_FLOAT_OF_BFP(gyro_float, imu.gyro); DOWNLINK_SEND_IMU_GYRO(_chan, &gyro_float.p, &gyro_float.q, &gyro_float.r)}
|
||||
# include "subsystems/imu.h"
|
||||
# define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) { DOWNLINK_SEND_IMU_ACCEL_RAW(_chan, &imu.accel_unscaled.x, &imu.accel_unscaled.y, &imu.accel_unscaled.z)}
|
||||
# define PERIODIC_SEND_IMU_GYRO_RAW(_chan) { DOWNLINK_SEND_IMU_GYRO_RAW(_chan, &imu.gyro_unscaled.p, &imu.gyro_unscaled.q, &imu.gyro_unscaled.r)}
|
||||
# define PERIODIC_SEND_IMU_MAG_RAW(_chan) { DOWNLINK_SEND_IMU_MAG_RAW(_chan, &imu.mag_unscaled.x, &imu.mag_unscaled.y, &imu.mag_unscaled.z)}
|
||||
# define PERIODIC_SEND_IMU_ACCEL(_chan) { struct FloatVect3 accel_float; ACCELS_FLOAT_OF_BFP(accel_float, imu.accel); DOWNLINK_SEND_IMU_ACCEL(_chan, &accel_float.x, &accel_float.y, &accel_float.z)}
|
||||
# define PERIODIC_SEND_IMU_GYRO(_chan) { struct FloatRates gyro_float; RATES_FLOAT_OF_BFP(gyro_float, imu.gyro); DOWNLINK_SEND_IMU_GYRO(_chan, &gyro_float.p, &gyro_float.q, &gyro_float.r)}
|
||||
# ifdef USE_MAGNETOMETER
|
||||
# define PERIODIC_SEND_IMU_MAG(_chan) { struct FloatVect3 mag_float; MAGS_FLOAT_OF_BFP(mag_float, imu.mag); DOWNLINK_SEND_IMU_MAG(_chan, &mag_float.x, &mag_float.y, &mag_float.z)}
|
||||
# else
|
||||
# define PERIODIC_SEND_IMU_MAG_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_MAG(_chan) {}
|
||||
# endif
|
||||
#else
|
||||
#define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) {}
|
||||
#define PERIODIC_SEND_IMU_GYRO_RAW(_chan) {}
|
||||
#define PERIODIC_SEND_IMU_MAG_RAW(_chan) {}
|
||||
#define PERIODIC_SEND_IMU_ACCEL(_chan) {}
|
||||
#define PERIODIC_SEND_IMU_GYRO(_chan) {}
|
||||
#define PERIODIC_SEND_IMU_MAG(_chan) {}
|
||||
# ifdef INS_MODULE_H
|
||||
# include "modules/ins/ins_module.h"
|
||||
# define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_GYRO_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_MAG_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_GYRO(_chan) { DOWNLINK_SEND_IMU_GYRO(_chan, &ins_p, &ins_q, &ins_r)}
|
||||
# define PERIODIC_SEND_IMU_ACCEL(_chan) { DOWNLINK_SEND_IMU_ACCEL(_chan, &ins_ax, &ins_ay, &ins_az)}
|
||||
# define PERIODIC_SEND_IMU_MAG(_chan) { DOWNLINK_SEND_IMU_MAG(_chan, &ins_mx, &ins_my, &ins_mz)}
|
||||
# else
|
||||
# define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_GYRO_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_MAG_RAW(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_ACCEL(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_GYRO(_chan) {}
|
||||
# define PERIODIC_SEND_IMU_MAG(_chan) {}
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#ifdef IMU_ANALOG
|
||||
@@ -189,17 +199,21 @@
|
||||
#define PERIODIC_SEND_TUNE_ROLL(_chan) DOWNLINK_SEND_TUNE_ROLL(_chan, &estimator_p,&estimator_phi, &h_ctl_roll_setpoint);
|
||||
|
||||
#if defined USE_GPS || defined SITL || defined USE_GPS_XSENS
|
||||
#define PERIODIC_SEND_GPS_SOL(_chan) DOWNLINK_SEND_GPS_SOL(_chan, &gps_Pacc, &gps_Sacc, &gps_PDOP, &gps_numSV)
|
||||
#define PERIODIC_SEND_GPS_SOL(_chan) DOWNLINK_SEND_GPS_SOL(_chan, &gps.pacc, &gps.sacc, &gps.pdop, &gps.num_sv)
|
||||
#endif
|
||||
|
||||
/* add by Haiyang Chao for debugging msg used by osam_imu*/
|
||||
#if defined UGEAR
|
||||
#define PERIODIC_SEND_GPS(_chan) DOWNLINK_SEND_GPS(_chan, &gps_mode, &gps_utm_east, &gps_utm_north, &gps_course, &gps_alt, &gps_gspeed,&gps_climb, &gps_week, &gps_itow, &gps_utm_zone, &gps_nb_ovrn)
|
||||
#define PERIODIC_SEND_GPS_SOL(_chan) DOWNLINK_SEND_GPS_SOL(_chan, &gps_Pacc, &gps_Sacc, &gps_PDOP, &gps_numSV)
|
||||
#define PERIODIC_SEND_DebugChao(_chan) DOWNLINK_SEND_DebugChao(_chan, &ugear_debug1, &ugear_debug2, &ugear_debug3, &ugear_debug4, &ugear_debug5, &ugear_debug6)
|
||||
#else
|
||||
#define PERIODIC_SEND_GPS(_chan) gps_send()
|
||||
#endif
|
||||
#define PERIODIC_SEND_GPS(_chan) { \
|
||||
static uint8_t i; \
|
||||
int16_t climb = -gps.ned_vel.z; \
|
||||
int16_t course = (DegOfRad(gps.course)/((int32_t)1e6)); \
|
||||
DOWNLINK_SEND_GPS(DefaultChannel, &gps.fix, &gps.utm_pos.east, &gps.utm_pos.north, &course, &gps.lla_pos.alt, &gps.gspeed, &climb, &gps.week, &gps.tow, &gps.utm_pos.zone, &i); \
|
||||
if ((gps.fix != GPS_FIX_3D) && (i >= gps.nb_channels)) i = 0; \
|
||||
if (i >= gps.nb_channels * 2) i = 0; \
|
||||
if (i < gps.nb_channels && gps.svinfos[i].cno > 0) { \
|
||||
DOWNLINK_SEND_SVINFO(DefaultChannel, &i, &gps.svinfos[i].svid, &gps.svinfos[i].flags, &gps.svinfos[i].qi, &gps.svinfos[i].cno, &gps.svinfos[i].elev, &gps.svinfos[i].azim); \
|
||||
} \
|
||||
i++; \
|
||||
}
|
||||
|
||||
#ifdef USE_BARO_MS5534A
|
||||
//#include "baro_MS5534A.h"
|
||||
|
||||
@@ -1,4 +0,0 @@
|
||||
#ifndef GPS_HW_H
|
||||
#define GPS_HW_H
|
||||
|
||||
#endif /* GPS_HW_H */
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user