mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-05 23:49:00 +08:00
Merge some fixes from branch 'v3.9'
* fix sending of I2C errors via telemetry
* we can't pass the address of a volatile var to the downlink macros:
it will be cast to (const uint8_t*) and read byte by byte and hence not work properly if it is volatile
* you will also rightly get a warning "cast discards qualifiers from pointer target type"
* so we need to copy it to a non-volatile var before sending
* make it possible to configure lisa/m 1.0 to use luftboot and also print a message if luftboot is assumed to be installed when flashing
* fix spi for navgo board
* updates for ENAC blender quadrotor
* fixed/updated some ctl_ settings files
* fix asctec v1 driver for new command scale
This commit is contained in:
+8
-2
@@ -100,10 +100,16 @@ else
|
||||
OOCD_BOARD = $($(TARGET).OOCD_BOARD)
|
||||
endif
|
||||
|
||||
ifndef NO_LUFTBOOT
|
||||
# default: assume the luftboot bootloader is used
|
||||
# if luftboot is not used define NO_LUFTBOOT to a value != 0
|
||||
OOCD_START_SECTOR = 4
|
||||
else
|
||||
ASSUMING_LUFTBOOT = "yes"
|
||||
ifdef NO_LUFTBOOT
|
||||
$(shell echo luftboot: $(NO_LUFTBOOT))
|
||||
ifneq ($(NO_LUFTBOOT),0)
|
||||
OOCD_START_SECTOR = 0
|
||||
ASSUMING_LUFTBOOT = "no"
|
||||
endif
|
||||
endif
|
||||
|
||||
# input files
|
||||
|
||||
@@ -3,17 +3,16 @@
|
||||
<modules main_freq="512">
|
||||
<!--load name="booz_pwm.xml">
|
||||
<define name="USE_PWM1"/>
|
||||
</load>
|
||||
<load name="booz_drop.xml"/>
|
||||
</load-->
|
||||
<!--load name="booz_drop.xml"/>
|
||||
<load name="booz_cam.xml"/-->
|
||||
<!--load name="sonar_maxbotix_booz.xml"/-->
|
||||
</modules>
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<define name="USE_INS_NAV_INIT"/>
|
||||
<!--define name="GUIDANCE_H_USE_REF"/-->
|
||||
|
||||
<target name="ap" board="booz_1.0">
|
||||
<target name="ap" board="navgo_1.0">
|
||||
<define name="FAILSAFE_GROUND_DETECT"/>
|
||||
<define name="USE_GPS_ACC4R"/>
|
||||
<define name="ACTUATORS_START_DELAY" value="3"/>
|
||||
@@ -27,29 +26,20 @@
|
||||
<subsystem name="actuators" type="skiron">
|
||||
<define name="SKIRON_I2C_SCL_TIME" value="25"/>
|
||||
</subsystem>
|
||||
<subsystem name="imu" type="b2_v1.1"/>
|
||||
<subsystem name="imu" type="navgo"/>
|
||||
<subsystem name="gps" type="ublox">
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
<configure name="GPS_BAUD" value="B57600"/>
|
||||
</subsystem>
|
||||
<subsystem name="stabilization" type="euler"/>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler">
|
||||
<define name="USE_NOISE_FILTER"/>
|
||||
</subsystem>
|
||||
<subsystem name="ahrs" type="int_cmpl_euler"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
</firmware>
|
||||
|
||||
<firmware name="booz_test_progs">
|
||||
<target name="test_telemetry" board="booz_1.0"/>
|
||||
<target name="test_baro" board="booz_1.0"/>
|
||||
<target name="test_rc_spektrum" board="booz_1.0"/>
|
||||
<target name="test_rc_ppm" board="booz_1.0"/>
|
||||
</firmware>
|
||||
|
||||
<servos min="0" neutral="0" max="0xff">
|
||||
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/>
|
||||
<servo name="BACK" no="2" min="0" neutral="0" max="255"/>
|
||||
<servo name="RIGHT" no="1" min="0" neutral="0" max="255"/>
|
||||
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
|
||||
<servo name="FRONT" no="0" min="0" neutral="0" max="255"/>
|
||||
<servo name="BACK" no="2" min="0" neutral="0" max="255"/>
|
||||
<servo name="RIGHT" no="1" min="0" neutral="0" max="255"/>
|
||||
<servo name="LEFT" no="3" min="0" neutral="0" max="255"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
@@ -67,8 +57,8 @@
|
||||
<section name="SUPERVISION" prefix="SUPERVISION_">
|
||||
<define name="MIN_MOTOR" value="20"/>
|
||||
<define name="MAX_MOTOR" value="255"/>
|
||||
<define name="TRIM_A" value="6"/>
|
||||
<define name="TRIM_E" value="0"/>
|
||||
<define name="TRIM_A" value="-3"/>
|
||||
<define name="TRIM_E" value="-3"/>
|
||||
<define name="TRIM_R" value="0"/>
|
||||
<define name="NB_MOTOR" value="4"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
@@ -80,49 +70,54 @@
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
|
||||
<define name="GYRO_P_CHAN" value="1"/>
|
||||
<define name="GYRO_Q_CHAN" value="0"/>
|
||||
<define name="GYRO_R_CHAN" value="2"/>
|
||||
<define name="GYRO_P_NEUTRAL" value="10"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="-32"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="11"/>
|
||||
|
||||
<define name="GYRO_P_NEUTRAL" value="33100"/>
|
||||
<define name="GYRO_Q_NEUTRAL" value="32440"/>
|
||||
<define name="GYRO_R_NEUTRAL" value="33033"/>
|
||||
<!-- SENS ITG3200 1/14.375 (deg/s)/LSB, rate frac 12bit => 1/14.375 * pi / 180 * 2^12 -->
|
||||
<define name="GYRO_P_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="4.97312" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="4.97312" integer="16"/>
|
||||
|
||||
<define name="GYRO_P_SENS" value="1.00" integer="16"/>
|
||||
<define name="GYRO_Q_SENS" value="1.00" integer="16"/>
|
||||
<define name="GYRO_R_SENS" value="1.00" integer="16"/>
|
||||
<define name="ACCEL_X_NEUTRAL" value="9"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="14"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-16"/>
|
||||
|
||||
<define name="ACCEL_X_CHAN" value="5"/>
|
||||
<define name="ACCEL_Y_CHAN" value="3"/>
|
||||
<define name="ACCEL_Z_CHAN" value="4"/>
|
||||
<!-- SENS ADXL345 16G 31.2 mg/LSB, accel frac 10bit => 31.2 * 2^10 / 1000 = 31.9488-->
|
||||
<define name="ACCEL_X_SENS" value="38.5866088465" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="38.7212932023" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="39.403098907" integer="16"/>
|
||||
|
||||
<define name="ACCEL_X_NEUTRAL" value="32932"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="32251"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="32463"/>
|
||||
<define name="MAG_X_NEUTRAL" value="80"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-271"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="112"/>
|
||||
|
||||
<define name="ACCEL_X_SENS" value="2.59502439625" integer="16"/>
|
||||
<define name="ACCEL_Y_SENS" value="2.57636806334" integer="16"/>
|
||||
<define name="ACCEL_Z_SENS" value="2.59680479039" integer="16"/>
|
||||
|
||||
<define name="MAG_X_CHAN" value="0"/>
|
||||
<define name="MAG_Y_CHAN" value="1"/>
|
||||
<define name="MAG_Z_CHAN" value="2"/>
|
||||
|
||||
<define name="MAG_X_NEUTRAL" value="-75"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="17"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="7"/>
|
||||
|
||||
<define name="MAG_X_SENS" value="5.50726991669" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="5.43740121157" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="2.60492836649" integer="16"/>
|
||||
<define name="MAG_X_SENS" value="4.44131219218" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="4.56234629213" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="5.298653926" integer="16"/>
|
||||
|
||||
<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="45." unit="deg"/-->
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
|
||||
</section>
|
||||
|
||||
<!-- Magnetic field for Toulouse (declination -16°) -->
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<define name="MAG_UPDATE_YAW_ONLY" value="1"/>
|
||||
<define name="PROPAGATE_FREQUENCY" value="512"/>
|
||||
<define name="H_X" value=" 0.513081"/>
|
||||
<define name="H_Y" value="-0.00242783"/>
|
||||
<define name="H_Z" value=" 0.858336"/>
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<!-- datasheet 1.4 mm/LSB : 0.0014*2^8 = 0.3584 -->
|
||||
<!-- calibration SENS = 1.156 :( -->
|
||||
<define name="BARO_SENS" value="1.156" integer="16"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
@@ -160,30 +155,25 @@
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(900.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="400"/>
|
||||
<define name="PHI_DGAIN" value="160"/>
|
||||
<define name="PHI_IGAIN" value="40"/>
|
||||
<define name="PHI_PGAIN" value="450"/>
|
||||
<define name="PHI_DGAIN" value="190"/>
|
||||
<define name="PHI_IGAIN" value="100"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="400"/>
|
||||
<define name="THETA_DGAIN" value="160"/>
|
||||
<define name="THETA_IGAIN" value="40"/>
|
||||
<define name="THETA_PGAIN" value="450"/>
|
||||
<define name="THETA_DGAIN" value="190"/>
|
||||
<define name="THETA_IGAIN" value="100"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="1000"/>
|
||||
<define name="PSI_DGAIN" value="350"/>
|
||||
<define name="PSI_IGAIN" value="10"/>
|
||||
<define name="PSI_PGAIN" value="700"/>
|
||||
<define name="PSI_DGAIN" value="250"/>
|
||||
<define name="PSI_IGAIN" value="20"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value=" 300"/>
|
||||
<define name="THETA_DDGAIN" value=" 300"/>
|
||||
<define name="PSI_DDGAIN" value=" 300"/>
|
||||
<define name="PHI_DDGAIN" value=" 100"/>
|
||||
<define name="THETA_DDGAIN" value=" 100"/>
|
||||
<define name="PSI_DDGAIN" value=" 100"/>
|
||||
|
||||
</section>
|
||||
|
||||
<section name="INS" prefix="INS_">
|
||||
<define name="BARO_SENS" value="16.5" integer="16"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
|
||||
<define name="MIN_ERR_Z" value="POS_BFP_OF_REAL(-10.)"/>
|
||||
@@ -195,8 +185,8 @@
|
||||
<define name="REF_MAX_ZDD" value=" 0.8*9.81"/>
|
||||
<define name="REF_MIN_ZD" value="-1.5"/>
|
||||
<define name="REF_MAX_ZD" value=" 1.5"/>
|
||||
<define name="HOVER_KP" value="400"/>
|
||||
<define name="HOVER_KD" value="200"/>
|
||||
<define name="HOVER_KP" value="300"/>
|
||||
<define name="HOVER_KD" value="160"/>
|
||||
<define name="HOVER_KI" value="0"/>
|
||||
<!-- SPEED_BFP_OF_REAL(1.5) / (MAX_PPRZ/2) -->
|
||||
<define name="RC_CLIMB_COEF" value ="163"/>
|
||||
@@ -215,13 +205,13 @@
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="VoltageOfAdc(adc)" value="(0.025*adc)"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_ATTITUDE_Z_HOLD"/>
|
||||
<!--define name="MODE_AUTO2" value="AP_MODE_NAV"/-->
|
||||
</section>
|
||||
|
||||
<section name="FMS">
|
||||
@@ -238,16 +228,14 @@
|
||||
<define name="PAN_MIN" value="0"/>
|
||||
<define name="PAN_MAX" value="25736"/> <!-- 360 deg (2^12) -->
|
||||
<define name="DEFAULT_MODE" value="BOOZ_CAM_MODE_MANUAL"/>
|
||||
<define name="SetPwm(_v)" value="Booz2SetPwm1Value(_v)"/>
|
||||
<!--define name="SetPwm(_v)" value="Booz2SetPwm1Value(_v)"/-->
|
||||
</section>
|
||||
|
||||
|
||||
<section name="MISC">
|
||||
<define name="BOOZ_ANALOG_BARO_THRESHOLD" value="800"/>
|
||||
<define name="FACE_REINJ_1" value="1024"/>
|
||||
<define name="DEFAULT_CIRCLE_RADIUS" value="10."/>
|
||||
<define name="BoozDropPwm(_v)" value="BoozSetPwm0Value(_v)"/>
|
||||
<define name="IMU_MAG_OFFSET" value="RadOfDeg(-9.)"/>
|
||||
<define name="BoozDropPwm(_v)" value="BoozSetPwm1Value(_v)"/>
|
||||
<!--define name="IMU_MAG_OFFSET" value="-9."/-->
|
||||
</section>
|
||||
|
||||
<section name="GCS">
|
||||
|
||||
@@ -8,7 +8,9 @@
|
||||
BOARD=lisa_m
|
||||
BOARD_VERSION=1.0
|
||||
BOARD_CFG=\"boards/$(BOARD)_$(BOARD_VERSION).h\"
|
||||
ifndef NO_LUFTBOOT
|
||||
NO_LUFTBOOT=1
|
||||
endif
|
||||
|
||||
ARCH=stm32
|
||||
$(TARGET).ARCHDIR = $(ARCH)
|
||||
|
||||
@@ -1,6 +1,5 @@
|
||||
<?xml version="1.0"?>
|
||||
<conf>
|
||||
<!-- arm7 aircrafts -->
|
||||
|
||||
<!-- booz2 -->
|
||||
<aircraft
|
||||
@@ -44,7 +43,7 @@
|
||||
radio="radios/cockpitMM.xml"
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/infrared.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/infrared.xml"
|
||||
gui_color="#6293ba"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -54,7 +53,7 @@
|
||||
radio="radios/cockpitSX.xml"
|
||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_tuning.xml settings/estimation/ins_neutrals.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/ins_neutrals.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -64,7 +63,7 @@
|
||||
radio="radios/cockpitMM.xml"
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_tuning.xml settings/estimation/infrared.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/control/ctl_basic.xml settings/estimation/infrared.xml"
|
||||
gui_color="#ba6293"
|
||||
/>
|
||||
<aircraft
|
||||
@@ -73,8 +72,8 @@
|
||||
airframe="airframes/examples/easystar_ets.xml"
|
||||
radio="radios/cockpitSX.xml"
|
||||
telemetry="telemetry/default_fixedwing.xml"
|
||||
flight_plan="flight_plans/versatile.xml"
|
||||
settings="settings/fixedwing_tuning.xml settings/estimation/infrared.xml"
|
||||
flight_plan="flight_plans/basic.xml"
|
||||
settings="settings/fixedwing_basic.xml settings/estimation/infrared.xml"
|
||||
gui_color="red"
|
||||
/>
|
||||
|
||||
|
||||
@@ -142,10 +142,11 @@ ap.CFLAGS += -DUSE_I2C2
|
||||
else ifeq ($(BOARD), lisa_m)
|
||||
ap.CFLAGS += -DUSE_I2C2
|
||||
else ifeq ($(BOARD), navgo)
|
||||
include $(CFG_ROTORCRAFT)/spi.makefile
|
||||
ap.CFLAGS += -DUSE_SPI
|
||||
ap.CFLAGS += -DUSE_SPI_SLAVE0
|
||||
ap.CFLAGS += -DSPI_NO_UNSELECT_SLAVE
|
||||
ap.CFLAGS += -DSPI_MASTER
|
||||
ap.srcs += mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c
|
||||
ap.srcs += peripherals/mcp355x.c
|
||||
endif
|
||||
ifneq ($(BARO_LED),none)
|
||||
|
||||
@@ -45,9 +45,9 @@
|
||||
|
||||
<!DOCTYPE radio SYSTEM "radio.dtd">
|
||||
<radio name="cockpitSX (easy)" data_min="900" data_max="2100" sync_min ="5000" sync_max ="15000" pulse_type="POSITIVE">
|
||||
<channel ctl="D" function="ROLL" max="2050" neutral="1500" min="950" average="0"/>
|
||||
<channel ctl="D" function="ROLL" min="2050" neutral="1500" max="950" average="0"/>
|
||||
<channel ctl="C" function="PITCH" min="2050" neutral="1500" max="950" average="0"/>
|
||||
<channel ctl="B" function="YAW" min="2050" neutral="1500" max="950" average="0"/>
|
||||
<channel ctl="B" function="YAW" min="950" neutral="1500" max="2050" average="0"/>
|
||||
<channel ctl="A" function="THROTTLE" min="1223" neutral="1223" max="2050" average="0"/>
|
||||
<channel ctl="G" function="UNUSED" min="2050" neutral="1500" max="950" average="1"/> <!-- center slider -->
|
||||
<channel ctl="E" function="GAIN1" min="2050" neutral="1496" max="948" average="1"/> <!-- top right slider -->
|
||||
|
||||
@@ -1,32 +1,9 @@
|
||||
<!DOCTYPE settings SYSTEM "settings.dtd">
|
||||
<!DOCTYPE settings SYSTEM "../settings.dtd">
|
||||
|
||||
<!-- A conf to use to tune a new A/C -->
|
||||
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="flight params">
|
||||
<dl_setting MAX="1000" MIN="0" STEP="10" VAR="flight_altitude" shortname="altitude"/>
|
||||
<dl_setting MAX="10" MIN="-10" STEP="0.5" VAR="wind_east"/>
|
||||
<dl_setting MAX="10" MIN="-10" STEP="0.5" VAR="wind_north"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="mode">
|
||||
<dl_setting MAX="2" MIN="0" STEP="1" VAR="pprz_mode" module="autopilot"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="alt_kalman_enabled" shortname="alt_kalman" module="estimator"/>
|
||||
<dl_setting MAX="0" MIN="0" STEP="1" VAR="estimator_flight_time" shortname="flight time"/>
|
||||
<dl_setting MAX="1000" MIN="0" STEP="1" VAR="stage_time"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="launch"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="1" VAR="kill_throttle"/>
|
||||
<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"/>
|
||||
<strip_button icon="circle-left.png" name="Circle left" value="-1"/>
|
||||
<key_press key="greater" value="1"/>
|
||||
<key_press key="less" value="-1"/>
|
||||
</dl_setting>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="control">
|
||||
|
||||
<dl_settings NAME="trim">
|
||||
@@ -52,15 +29,13 @@
|
||||
|
||||
<dl_settings name="auto_throttle">
|
||||
<dl_setting MAX="1" MIN="0.0" STEP="0.05" VAR="v_ctl_auto_throttle_cruise_throttle" shortname="cruise throttle" module="guidance/guidance_v" handler="SetCruiseThrottle" param="V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE">
|
||||
<strip_button name="Loiter" value="0.1"/>
|
||||
<strip_button name="Cruise" value="0"/>
|
||||
<strip_button name="Dash" value="1"/>
|
||||
<strip_button name="Loiter" value="0.1" group="dash_loiter"/>
|
||||
<strip_button name="Cruise" value="0" group="dash_loiter"/>
|
||||
<strip_button name="Dash" value="1" group="dash_loiter"/>
|
||||
</dl_setting>
|
||||
<dl_setting MAX="0.05" MIN="0.00" STEP="0.005" VAR="v_ctl_auto_throttle_pgain" shortname="throttle_pgain" param="V_CTL_AUTO_THROTTLE_PGAIN"/>
|
||||
<dl_setting MAX="1" MIN="0.0" STEP="0.05" VAR="v_ctl_auto_throttle_igain" shortname="throttle_igain" param="V_CTL_AUTO_THROTTLE_IGAIN"/>
|
||||
<dl_setting MAX="2" MIN="0.0" STEP="0.1" VAR="v_ctl_auto_throttle_dgain" shortname="throttle_dgain"/>
|
||||
<dl_setting MAX="0" MIN="-4000" STEP="100" VAR="v_ctl_auto_throttle_dash_trim" shortname="dash trim"/>
|
||||
<dl_setting MIN="0" MAX="3000" STEP="100" VAR="v_ctl_auto_throttle_loiter_trim" shortname="loiter trim" param="V_CTL_AUTO_THROTTLE_LOITER_TRIM"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="0.01" VAR="v_ctl_auto_throttle_climb_throttle_increment" shortname="throttle_incr" param="V_CTL_AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT"/>
|
||||
<dl_setting MAX="1" MIN="0" STEP="0.01" VAR="v_ctl_auto_throttle_pitch_of_vz_pgain" shortname="pitch_of_vz" param="V_CTL_AUTO_THROTTLE_PITCH_OF_VZ_PGAIN"/>
|
||||
<dl_setting MAX="10" MIN="-10" STEP="0.1" VAR="v_ctl_auto_throttle_pitch_of_vz_dgain" shortname="pitch_of_vz (d)"/>
|
||||
@@ -0,0 +1,12 @@
|
||||
<!DOCTYPE settings SYSTEM "../settings.dtd">
|
||||
|
||||
<!-- Set dash and loiter trim -->
|
||||
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="0" MIN="-4000" STEP="100" VAR="v_ctl_auto_throttle_dash_trim" shortname="dash trim" param="V_CTL_AUTO_THROTTLE_DASH_TRIM" module="stabilization/stabilization_attitude"/>
|
||||
<dl_setting MIN="0" MAX="3000" STEP="100" VAR="v_ctl_auto_throttle_loiter_trim" shortname="loiter trim" param="V_CTL_AUTO_THROTTLE_LOITER_TRIM"/>
|
||||
</dl_settings>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
@@ -34,6 +34,11 @@
|
||||
#include "mcu_periph/i2c.h"
|
||||
#include "mcu_periph/sys_time.h"
|
||||
|
||||
#define ASCTEC_MIN_CMD -100
|
||||
#define ASCTEC_MAX_CMD 100
|
||||
|
||||
#define ASCTEC_MIN_THROTTLE 0
|
||||
#define ASCTEC_MAX_THROTTLE 200
|
||||
|
||||
struct ActuatorsAsctec actuators_asctec;
|
||||
|
||||
@@ -86,15 +91,15 @@ void actuators_set(bool_t motors_on) {
|
||||
actuators_asctec.cmds[YAW] = 0;
|
||||
actuators_asctec.cmds[THRUST] = 0;
|
||||
#else /* ! KILL_MOTORS */
|
||||
actuators_asctec.cmds[PITCH] = commands[COMMAND_PITCH] + SUPERVISION_TRIM_E;
|
||||
actuators_asctec.cmds[ROLL] = commands[COMMAND_ROLL] + SUPERVISION_TRIM_A;
|
||||
actuators_asctec.cmds[YAW] = commands[COMMAND_YAW] + SUPERVISION_TRIM_R;
|
||||
actuators_asctec.cmds[THRUST] = commands[COMMAND_THRUST];
|
||||
Bound(actuators_asctec.cmds[PITCH],-100, 100);
|
||||
Bound(actuators_asctec.cmds[ROLL], -100, 100);
|
||||
Bound(actuators_asctec.cmds[YAW], -100, 100);
|
||||
actuators_asctec.cmds[PITCH] = ((commands[COMMAND_PITCH] + SUPERVISION_TRIM_E) * ASCTEC_MAX_CMD) / MAX_PPRZ;
|
||||
actuators_asctec.cmds[ROLL] = ((commands[COMMAND_ROLL] + SUPERVISION_TRIM_A) * ASCTEC_MAX_CMD) / MAX_PPRZ;
|
||||
actuators_asctec.cmds[YAW] = ((commands[COMMAND_YAW] + SUPERVISION_TRIM_R) * ASCTEC_MAX_CMD) / MAX_PPRZ;
|
||||
actuators_asctec.cmds[THRUST] = (commands[COMMAND_THRUST] * ASCTEC_MAX_THROTTLE) / MAX_PPRZ;
|
||||
Bound(actuators_asctec.cmds[PITCH],ASCTEC_MIN_CMD, ASCTEC_MAX_CMD);
|
||||
Bound(actuators_asctec.cmds[ROLL], ASCTEC_MIN_CMD, ASCTEC_MAX_CMD);
|
||||
Bound(actuators_asctec.cmds[YAW], ASCTEC_MIN_CMD, ASCTEC_MAX_CMD);
|
||||
if (motors_on) {
|
||||
Bound(actuators_asctec.cmds[THRUST], 1, 200);
|
||||
Bound(actuators_asctec.cmds[THRUST], ASCTEC_MIN_THROTTLE + 1, ASCTEC_MAX_THROTTLE);
|
||||
}
|
||||
else
|
||||
actuators_asctec.cmds[THRUST] = 0;
|
||||
@@ -121,7 +126,7 @@ void actuators_set(bool_t motors_on) {
|
||||
actuators_asctec.cur_addr = actuators_asctec.new_addr;
|
||||
break;
|
||||
case NONE:
|
||||
actuators_asctec.i2c_trans.buf[0] = 100 - actuators_asctec.cmds[PITCH];
|
||||
actuators_asctec.i2c_trans.buf[0] = 100 - actuators_asctec.cmds[PITCH];
|
||||
actuators_asctec.i2c_trans.buf[1] = 100 + actuators_asctec.cmds[ROLL];
|
||||
actuators_asctec.i2c_trans.buf[2] = 100 - actuators_asctec.cmds[YAW];
|
||||
actuators_asctec.i2c_trans.buf[3] = actuators_asctec.cmds[THRUST];
|
||||
|
||||
@@ -739,44 +739,89 @@
|
||||
&ahrs.ltp_to_body_euler.psi); \
|
||||
}
|
||||
|
||||
#ifdef USE_I2C0
|
||||
#define PERIODIC_SEND_I2C0_ERRORS(_trans, _dev) { \
|
||||
uint16_t i2c0_ack_fail_cnt = i2c0.errors->ack_fail_cnt; \
|
||||
uint16_t i2c0_miss_start_stop_cnt = i2c0.errors->miss_start_stop_cnt; \
|
||||
uint16_t i2c0_arb_lost_cnt = i2c0.errors->arb_lost_cnt; \
|
||||
uint16_t i2c0_over_under_cnt = i2c0.errors->over_under_cnt; \
|
||||
uint16_t i2c0_pec_recep_cnt = i2c0.errors->pec_recep_cnt; \
|
||||
uint16_t i2c0_timeout_tlow_cnt = i2c0.errors->timeout_tlow_cnt; \
|
||||
uint16_t i2c0_smbus_alert_cnt = i2c0.errors->smbus_alert_cnt; \
|
||||
uint16_t i2c0_unexpected_event_cnt = i2c0.errors->unexpected_event_cnt; \
|
||||
uint32_t i2c0_last_unexpected_event = i2c0.errors->last_unexpected_event; \
|
||||
DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \
|
||||
&i2c0_ack_fail_cnt, \
|
||||
&i2c0_miss_start_stop_cnt, \
|
||||
&i2c0_arb_lost_cnt, \
|
||||
&i2c0_over_under_cnt, \
|
||||
&i2c0_pec_recep_cnt, \
|
||||
&i2c0_timeout_tlow_cnt, \
|
||||
&i2c0_smbus_alert_cnt, \
|
||||
&i2c0_unexpected_event_cnt, \
|
||||
&i2c0_last_unexpected_event); \
|
||||
}
|
||||
#else
|
||||
#define PERIODIC_SEND_I2C0_ERRORS(_trans, _dev) {}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C1
|
||||
#define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) { \
|
||||
DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \
|
||||
&i2c1.errors->ack_fail_cnt, \
|
||||
&i2c1.errors->miss_start_stop_cnt, \
|
||||
&i2c1.errors->arb_lost_cnt, \
|
||||
&i2c1.errors->over_under_cnt, \
|
||||
&i2c1.errors->pec_recep_cnt, \
|
||||
&i2c1.errors->timeout_tlow_cnt, \
|
||||
&i2c1.errors->smbus_alert_cnt, \
|
||||
&i2c1.errors->unexpected_event_cnt, \
|
||||
&i2c1.errors->last_unexpected_event); \
|
||||
#define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) { \
|
||||
uint16_t i2c1_ack_fail_cnt = i2c1.errors->ack_fail_cnt; \
|
||||
uint16_t i2c1_miss_start_stop_cnt = i2c1.errors->miss_start_stop_cnt; \
|
||||
uint16_t i2c1_arb_lost_cnt = i2c1.errors->arb_lost_cnt; \
|
||||
uint16_t i2c1_over_under_cnt = i2c1.errors->over_under_cnt; \
|
||||
uint16_t i2c1_pec_recep_cnt = i2c1.errors->pec_recep_cnt; \
|
||||
uint16_t i2c1_timeout_tlow_cnt = i2c1.errors->timeout_tlow_cnt; \
|
||||
uint16_t i2c1_smbus_alert_cnt = i2c1.errors->smbus_alert_cnt; \
|
||||
uint16_t i2c1_unexpected_event_cnt = i2c1.errors->unexpected_event_cnt; \
|
||||
uint32_t i2c1_last_unexpected_event = i2c1.errors->last_unexpected_event; \
|
||||
DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \
|
||||
&i2c1_ack_fail_cnt, \
|
||||
&i2c1_miss_start_stop_cnt, \
|
||||
&i2c1_arb_lost_cnt, \
|
||||
&i2c1_over_under_cnt, \
|
||||
&i2c1_pec_recep_cnt, \
|
||||
&i2c1_timeout_tlow_cnt, \
|
||||
&i2c1_smbus_alert_cnt, \
|
||||
&i2c1_unexpected_event_cnt, \
|
||||
&i2c1_last_unexpected_event); \
|
||||
}
|
||||
#else
|
||||
#define PERIODIC_SEND_I2C1_ERRORS(_trans, _dev) {}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C2
|
||||
#define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) { \
|
||||
DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \
|
||||
&i2c2.errors->ack_fail_cnt, \
|
||||
&i2c2.errors->miss_start_stop_cnt, \
|
||||
&i2c2.errors->arb_lost_cnt, \
|
||||
&i2c2.errors->over_under_cnt, \
|
||||
&i2c2.errors->pec_recep_cnt, \
|
||||
&i2c2.errors->timeout_tlow_cnt, \
|
||||
&i2c2.errors->smbus_alert_cnt, \
|
||||
&i2c2.errors->unexpected_event_cnt, \
|
||||
&i2c2.errors->last_unexpected_event); \
|
||||
#define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) { \
|
||||
uint16_t i2c2_ack_fail_cnt = i2c2.errors->ack_fail_cnt; \
|
||||
uint16_t i2c2_miss_start_stop_cnt = i2c2.errors->miss_start_stop_cnt; \
|
||||
uint16_t i2c2_arb_lost_cnt = i2c2.errors->arb_lost_cnt; \
|
||||
uint16_t i2c2_over_under_cnt = i2c2.errors->over_under_cnt; \
|
||||
uint16_t i2c2_pec_recep_cnt = i2c2.errors->pec_recep_cnt; \
|
||||
uint16_t i2c2_timeout_tlow_cnt = i2c2.errors->timeout_tlow_cnt; \
|
||||
uint16_t i2c2_smbus_alert_cnt = i2c2.errors->smbus_alert_cnt; \
|
||||
uint16_t i2c2_unexpected_event_cnt = i2c2.errors->unexpected_event_cnt; \
|
||||
uint32_t i2c2_last_unexpected_event = i2c2.errors->last_unexpected_event; \
|
||||
DOWNLINK_SEND_I2C_ERRORS(_trans, _dev, \
|
||||
&i2c2_ack_fail_cnt, \
|
||||
&i2c2_miss_start_stop_cnt, \
|
||||
&i2c2_arb_lost_cnt, \
|
||||
&i2c2_over_under_cnt, \
|
||||
&i2c2_pec_recep_cnt, \
|
||||
&i2c2_timeout_tlow_cnt, \
|
||||
&i2c2_smbus_alert_cnt, \
|
||||
&i2c2_unexpected_event_cnt, \
|
||||
&i2c2_last_unexpected_event); \
|
||||
}
|
||||
#else
|
||||
#define PERIODIC_SEND_I2C2_ERRORS(_trans, _dev) {}
|
||||
#endif
|
||||
|
||||
#define PERIODIC_SEND_I2C_ERRORS(_trans, _dev) { \
|
||||
PERIODIC_SEND_I2C1_ERRORS(_trans, _dev); \
|
||||
PERIODIC_SEND_I2C2_ERRORS(_trans, _dev); \
|
||||
}
|
||||
#define PERIODIC_SEND_I2C_ERRORS(_trans, _dev) { \
|
||||
PERIODIC_SEND_I2C0_ERRORS(_trans, _dev); \
|
||||
PERIODIC_SEND_I2C1_ERRORS(_trans, _dev); \
|
||||
PERIODIC_SEND_I2C2_ERRORS(_trans, _dev); \
|
||||
}
|
||||
|
||||
// FIXME: still used?? or replace by EXTRA_ADC
|
||||
#define PERIODIC_SEND_BOOZ2_SONAR(_trans, _dev) {}
|
||||
|
||||
Reference in New Issue
Block a user