Skip to content

Commit

Permalink
missing airframe was added.
Browse files Browse the repository at this point in the history
  • Loading branch information
dewagter committed Oct 6, 2018
1 parent 77e0759 commit 6dd1357
Show file tree
Hide file tree
Showing 3 changed files with 377 additions and 2 deletions.
265 changes: 265 additions & 0 deletions conf/airframes/tudelft/bebop2_detect_gate_front.xml
@@ -0,0 +1,265 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">

<airframe name="bebop2_optitrack_visionfront">
<description>Bebop2: Detects Autonomous-Drone-Race-Gates</description>

<firmware name="rotorcraft">
<target name="ap" board="bebop2">
<define name="SIMULATE" value="FALSE"/>
</target>
<target name="nps" board="pc">
<module name="fdm" type="gazebo"/>
</target>

<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="datalink"/>
<module name="stabilization" type="indi_simple"/>
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="FALSE"/>
<!-- <define name="AHRS_USE_GPS_HEADING" value="TRUE"/> -->
</module>
<define name="USE_SONAR" value="TRUE"/>
<module name="ins" type="extended"/>

<define name="MT9F002_OUTPUT_HEIGHT" value="640" />
<define name="MT9F002_OUTPUT_WIDTH" value="640" />
<define name="MT9F002_INITIAL_OFFSET_X" value="0.15" />
<define name="MT9F002_INITIAL_OFFSET_Y" value="0.0" />
<define name="MT9F002_TARGET_EXPOSURE" value="30" />
<define name="MT9F002_GAIN_GREEN1" value="4"/>
<define name="MT9F002_GAIN_GREEN2" value="4"/>
<define name="MT9F002_GAIN_RED" value="5"/>
<define name="MT9F002_GAIN_BLUE" value="5"/>
<define name="MT9F002_OUTPUT_SCALER" value="0.25"/>
<define name="MT9F002_X_ODD_INC_VAL" value="1"/>
<define name="MT9F002_Y_ODD_INC_VAL" value="1"/>

<module name="geo_mag"/>
<module name="air_data"/>
<module name="send_imu_mag_current"/>
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module>

<module name="video_thread"/>

<module name="video_capture">
<define name="VIDEO_CAPTURE_CAMERA" value="front_camera"/>
<define name="VIDEO_CAPTURE_PATH" value="/data/ftp/internal_000/images/"/>
</module>

<module name="pose_history">
<define name="POSE_HISTORY_SIZE" value="128" />
</module>

<!-- For tuning the color filter: -->
<!--
<module name="cv_colorfilter">
<define name="COLORFILTER_CAMERA" value="front_camera"/>
<define name="COLORFILTER_FPS" value="0"/>
</module>
-->

<module name="ctrl_module_outerloop_demo"/>

<module name="cv_detect_gate">
<define name="DETECT_GATE_CAMERA" value="front_camera"/>
<define name="DETECT_GATE_FPS" value="0"/>
<define name="DETECT_GATE_Y_MIN" value="31"/>
<define name="DETECT_GATE_Y_MAX" value="130"/>
<define name="DETECT_GATE_U_MIN" value="62"/>
<define name="DETECT_GATE_U_MAX" value="138"/>
<define name="DETECT_GATE_V_MIN" value="148"/>
<define name="DETECT_GATE_V_MAX" value="221"/>

</module>

<module name="video_rtp_stream">
<define name="VIEWVIDEO_CAMERA" value="front_camera"/>
<!-- <define name="VIEWVIDEO_CAMERA2" value="bottom_camera"/> -->
<define name="VIEWVIDEO_DOWNSIZE_FACTOR" value="4"/>
<define name="VIEWVIDEO_QUALITY_FACTOR" value="50"/>
</module>

<!--<module name="bebop_ae_awb"/>-->
</firmware>

<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="6000"/>
</commands>

<servos driver="Default">
<servo name="TOP_LEFT" no="0" min="2500" neutral="2500" max="12000"/>
<servo name="TOP_RIGHT" no="1" min="2500" neutral="2500" max="12000"/>
<servo name="BOTTOM_RIGHT" no="2" min="2500" neutral="2500" max="12000"/>
<servo name="BOTTOM_LEFT" no="3" min="2500" neutral="2500" max="12000"/>
</servos>

<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="REVERSE" value="TRUE"/>
<define name="TYPE" value="QUAD_X"/>
</section>

<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>

<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE"/>
<define name="CALC_TAS_FACTOR" value="FALSE"/>
<define name="CALC_AMSL_BARO" value="TRUE"/>
</section>

<!-- Magnetometer still needs to be calibrated -->
<section name="IMU" prefix="IMU_">
<define name="MAG_X_NEUTRAL" value="0"/>
<define name="MAG_Y_NEUTRAL" value="0"/>
<define name="MAG_Z_NEUTRAL" value="0"/>
<define name="MAG_X_SENS" value="7.28514789391" integer="16"/>
<define name="MAG_Y_SENS" value="7.33022132691" integer="16"/>
<define name="MAG_Z_SENS" value="7.57102035692" integer="16"/>
</section>

<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<!-- Use GPS heading instead of magneto -->
<define name="USE_GPS_HEADING" value="FALSE"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</section>

<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
<!-- Use GPS altitude measurments and set the R gain -->
<define name="USE_GPS_ALT" value="0"/>
<!-- <define name="VFF_R_GPS" value="0.01"/> -->
</section>


<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="300" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>
</section>

<section name="ATTITUDE_REFERENCE" prefix="STABILIZATION_ATTITUDE_">
<!-- attitude reference generation model -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>
</section>

<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_P" value="0.0397"/>
<define name="G1_Q" value="0.0299"/>
<define name="G1_R" value="0.0014"/>
<define name="G2_R" value="0.1219"/>

<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="600.0"/>
<define name="REF_ERR_Q" value="600.0"/>
<define name="REF_ERR_R" value="600.0"/>
<define name="REF_RATE_P" value="28.0"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>

<!--Maxium yaw rate, to avoid instability-->
<define name="MAX_R" value="120.0" unit="deg/s"/>

<!-- second order filter parameters -->
<define name="FILT_CUTOFF" value="8.0"/>
<define name="ESTIMATION_FILT_CUTOFF" value="8.0"/>

<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.1"/>
<define name="ACT_DYN_Q" value="0.1"/>
<define name="ACT_DYN_R" value="0.1"/>

<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>


<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="350"/>
<define name="HOVER_KD" value="85"/>
<define name="HOVER_KI" value="20"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="REF_MAX_SPEED" value="2" unit="m/s"/>
<define name="MAX_BANK" value="32" unit="deg"/>
<define name="PGAIN" value="220"/>
<define name="DGAIN" value="160"/>
<define name="IGAIN" value="15"/>
</section>

<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="1.0"/>
<define name="DESCEND_VSPEED" value="-1.0"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</section>
<include href="conf/simulator/gazebo/airframes/bebop.xml"/>

<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_MODULE"/>
<!-- <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="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>

<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="11.0" unit="V"/>
<define name="LOW_BAT_LEVEL" value="11.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
99 changes: 99 additions & 0 deletions conf/flight_plans/tudelft/rotorcraft_autonomous_drone_race.xml
@@ -0,0 +1,99 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">

<flight_plan alt="2.0" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="25" name="Rotorcraft Optitrack (Delft)" security_height="0.3" qfu="270">
<header>
// Note: use 'git submodule update --init -- sw/ext/tudelft_gazebo_models/'
// to download the required models.
#define NPS_GAZEBO_WORLD "drone_race_track_2018_actual_with_gate_papers.world"
</header>

<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="CLIMB" x="20" y="0"/>
<waypoint name="STDBY" x="0" y="0"/>
<waypoint name="TD" x="20" y="6"/>

<waypoint y="-4" x="0" name="G1"/>
<waypoint y="-4" x="0" name="G2"/>
<waypoint y="-4" x="0" name="G3"/>
<waypoint y="-4" x="0" name="G4"/>
<waypoint y="-4" x="0" name="G5"/>
<waypoint y="-4" x="0" name="G6"/>
<waypoint y="-4" x="0" name="G7"/>
<waypoint y="-4" x="0" name="G8"/>
<waypoint y="-4" x="0" name="G9"/>
<waypoint y="-4" x="0" name="G10"/>
<waypoint y="-4" x="0" name="G11"/>
<waypoint y="-4" x="0" name="G12"/>

<waypoint y="-6" x="0" name="p1"/>
<waypoint y="-6" x="0" name="p2"/>
<waypoint y="-6" x="0" name="p3"/>
<waypoint y="-6" x="0" name="p4"/>
<waypoint y="-6" x="0" name="p5"/>
<waypoint y="-6" x="0" name="p6"/>
<waypoint y="-6" x="0" name="p7"/>
<waypoint y="-6" x="0" name="p8"/>
<waypoint y="-6" x="0" name="p9"/>
<waypoint y="-6" x="0" name="p10"/>
<waypoint y="-6" x="0" name="p11"/>
<waypoint y="-6" x="0" name="p12"/>

<waypoint y="-5" x="-2" name="FA1"/>
<waypoint y="15" x="-2" name="FA2"/>
<waypoint y="15" x="12" name="FA3"/>
<waypoint y="-5" x="12" name="FA4"/>
</waypoints>
<sectors>
<sector color="red" name="Flight_Area_1">
<corner name="FA4"/>
<corner name="FA3"/>
<corner name="FA2"/>
<corner name="FA1"/>
</sector>
</sectors>
<blocks>
<block name="Holding point">
<call_once fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Start Engine">
<call_once fun="NavResurrect()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
<block name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
<exception cond="stateGetPositionEnu_f()->z > 1.0" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
</block>
<block name="route">
<go from="p1" hmode="route" wp="p2"/>
<go from="p2" hmode="route" wp="p3"/>
<go from="p3" hmode="route" wp="p4"/>
<go from="p4" hmode="route" wp="p5"/>
<go from="p5" hmode="route" wp="p6"/>
<go from="p6" hmode="route" wp="p7"/>
<go from="p7" hmode="route" wp="p8"/>
<go from="p8" hmode="route" wp="p9"/>
</block>
<block name="land here" strip_button="Land Here" strip_icon="land-right.png">
<call_once fun="NavSetWaypointHere(WP_TD)"/>
</block>
<block name="land">
<go wp="TD"/>
</block>
<block name="flare">
<exception cond="NavDetectGround()" deroute="Holding point"/>
<exception cond="!nav_is_in_flight()" deroute="landed"/>
<call_once fun="NavStartDetectGround()"/>
<stay climb="nav_descend_vspeed" vmode="climb" wp="TD"/>
</block>
<block name="landed">
<call_once fun="NavKillThrottle()"/>
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
</block>
</blocks>
</flight_plan>
15 changes: 13 additions & 2 deletions conf/userconf/tudelft/conf.xml
Expand Up @@ -425,9 +425,9 @@
airframe="airframes/tudelft/bebop_autonomous_race_2018.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
flight_plan="flight_plans/tudelft/rotorcraft_autonomous_drone_race.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/ctrl_module_outerloop_demo.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbc3bce5b"
/>
<aircraft
Expand All @@ -452,6 +452,17 @@
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#f6d5baaaffff"
/>
<aircraft
name="bebop2_detect_gate_front"
ac_id="218"
airframe="airframes/tudelft/bebop2_detect_gate_front.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/tudelft/rotorcraft_autonomous_drone_race.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/video_rtp_stream.xml modules/cv_detect_gate.xml modules/ctrl_module_outerloop_demo.xml modules/video_capture.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbf17bf17"
/>
<aircraft
name="bebop2_no_dampers"
ac_id="26"
Expand Down

0 comments on commit 6dd1357

Please sign in to comment.