mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-23 21:36:28 +08:00
MAVLab course2017 airframe: bebop orange avoid (#2170)
This commit is contained in:
committed by
GitHub
parent
b3b2b8f289
commit
08555b8366
@@ -0,0 +1,253 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<airframe name="bebop_avoider">
|
||||
<description>Vision Course TUDelft V2017
|
||||
</description>
|
||||
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="bebop"/>
|
||||
|
||||
<!-- Front Camera parameters -->
|
||||
<define name="H264_ROTATE" value="TRUE" />
|
||||
<define name="MT9F002_INITIAL_OFFSET_X" value="416+2704-480" /> <!-- 480 / 960 / 1920 / 3840 (horion for theta = 0 -> 2704) -->
|
||||
<define name="MT9F002_INITIAL_OFFSET_Y" value="1680-1040" /> <!-- 420 / 840 / 1680 / 3360 -->
|
||||
<define name="MT9F002_SENSOR_WIDTH" value="2*480" /> <!-- 480 / 960 / 1920 / 3840 -->
|
||||
<define name="MT9F002_SENSOR_HEIGHT" value="2*1040" /> <!-- 420 / 840 / 1680 / 3360 -->
|
||||
<define name="MT9F002_OUTPUT_WIDTH" value="240" /> <!-- 480 / 960 / 1920 / 3840 -->
|
||||
<define name="MT9F002_OUTPUT_HEIGHT" value="520" /> <!-- 420 / 840 / 1680 / 3360 -->
|
||||
<define name="MT9F002_TARGET_FPS" value="30" />
|
||||
<define name="MT9F002_TARGET_EXPOSURE" value="4" />
|
||||
<define name="MT9F002_GAIN_GREEN1" value="8.0" />
|
||||
<define name="MT9F002_GAIN_GREEN2" value="8.0" />
|
||||
<define name="MT9F002_GAIN_RED" value="8.0" />
|
||||
<define name="MT9F002_GAIN_BLUE" value="8.0" />
|
||||
|
||||
<!-- Subsystem section -->
|
||||
<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">
|
||||
<define name="INDI_RPM_FEEDBACK" value="TRUE" />
|
||||
</module>
|
||||
<module name="stabilization" type="rate_indi"/>
|
||||
<module name="ahrs" type="int_cmpl_quat">
|
||||
<configure name="USE_MAGNETOMETER" value="FALSE"/>
|
||||
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/>
|
||||
</module>
|
||||
<module name="ins" type="extended"/>
|
||||
<!-- <module name="guidance" type="indi"> <define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN"
|
||||
value="-500.0"/> <define name="GUIDANCE_INDI_THRUST_DYNAMICS" value="0.1"/>
|
||||
<define name="GUIDANCE_INDI_RC_DEBUG" value="TRUE"/> </module> -->
|
||||
</firmware>
|
||||
|
||||
<modules main_freq="512">
|
||||
<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>
|
||||
|
||||
<!-- Video/Camera modules -->
|
||||
<module name="video_thread" />
|
||||
<!--module name="cv_ae_awb">
|
||||
<define name="CV_AE_AWB_AV" value="1" />
|
||||
<define name="CV_AE_AWB_VERBOSE" value="0" />
|
||||
</module-->
|
||||
<module name="cv_colorfilter">
|
||||
<define name="COLORFILTER_CAMERA" value="front_camera" />
|
||||
</module>
|
||||
<module name="orange_avoider" />
|
||||
<module name="video_rtp_stream">
|
||||
<configure name="VIEWVIDEO_HOST" value="192.168.42.65" />
|
||||
<configure name="VIEWVIDEO_BROADCAST" value="FALSE" />
|
||||
<define name="VIEWVIDEO_CAMERA" value="front_camera" />
|
||||
<define name="VIEWVIDEO_SHOT_PATH" value="/data/ftp/internal_000" />
|
||||
<define name="VIEWVIDEO_FPS" value="18" />
|
||||
<define name="VIEWVIDEO_WRITE_VIDEO" value="FALSE" />
|
||||
<define name="VIEWVIDEO_VIDEO_FILE" value="orangeAvoider" />
|
||||
<define name="VIEWVIDEO_STREAM_VIDEO" value="TRUE" />
|
||||
</module>
|
||||
|
||||
</modules>
|
||||
|
||||
<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="3000" neutral="3000" max="9800" />
|
||||
<servo name="TOP_RIGHT" no="1" min="3000" neutral="3000" max="9800" />
|
||||
<servo name="BOTTOM_RIGHT" no="2" min="3000" neutral="3000" max="9800" />
|
||||
<servo name="BOTTOM_LEFT" no="3" min="3000" neutral="3000" max="9800" />
|
||||
</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>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</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"/>
|
||||
|
||||
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
|
||||
<define name="GRAVITY_HEURISTIC_FACTOR" 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="1"/>
|
||||
<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="120" 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.0639"/>
|
||||
<define name="G1_Q" value="0.0361"/>
|
||||
<define name="G1_R" value="0.0022"/>
|
||||
<define name="G2_R" value="0.1450"/>
|
||||
|
||||
<!-- 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="283"/>
|
||||
<define name="HOVER_KD" value="82"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.68"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
|
||||
|
||||
<define name="ADAPT_INITIAL_HOVER_THROTTLE" value="0.68" />
|
||||
<define name="ADAPT_MIN_HOVER_THROTTLE" value="0.55" />
|
||||
<define name="ADAPT_MAX_HOVER_THROTTLE" value="0.72" />
|
||||
<!-- <define name="ADAPT_NOISE_FACTOR" value="0.8" /> -->
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<!-- Good weather -->
|
||||
<define name="MAX_BANK" value="20" unit="deg"/>
|
||||
<define name="REF_MAX_SPEED" value="2" unit="m/s"/>
|
||||
<!-- Bad weather -->
|
||||
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
|
||||
<define name="PGAIN" value="120"/>
|
||||
<define name="DGAIN" value="230"/>
|
||||
<define name="IGAIN" value="40"/>
|
||||
</section>
|
||||
|
||||
<section name="NAVIGATION" prefix="NAV_">
|
||||
<define name="CLIMB_VSPEED" value="1.0"/>
|
||||
<define name="DESCEND_VSPEED" value="-0.75"/>
|
||||
</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>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
|
||||
<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="10.8" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="11.1" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
||||
</section>
|
||||
</airframe>
|
||||
@@ -1,124 +0,0 @@
|
||||
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
|
||||
|
||||
<flight_plan alt="1.5" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="8" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "autopilot.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "subsystems/datalink/datalink.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
<waypoint height="0" name="HOME" x="0.0" y="0.0"/>
|
||||
<waypoint height="5" name="CLIMB" x="1.2" y="-0.6"/>
|
||||
<waypoint name="GOAL" x="2.0" y="2.0"/>
|
||||
<waypoint height="1.342321" name="STDBY" x="-0.7" y="-0.8"/>
|
||||
<waypoint name="TD" x="0.8" y="-1.7"/>
|
||||
<waypoint lat="51.9906213" lon="4.3768628" name="_CZ1"/>
|
||||
<waypoint lat="51.9905874" lon="4.3767766" name="_CZ2"/>
|
||||
<waypoint lat="51.9906409" lon="4.3767226" name="_CZ3"/>
|
||||
<waypoint lat="51.990667" lon="4.376806" name="_CZ4"/>
|
||||
<waypoint lat="51.990624" lon="4.376845" name="_OZ1"/>
|
||||
<waypoint lat="51.990601" lon="4.376782" name="_OZ2"/>
|
||||
<waypoint alt="11.5" lat="51.990638" lon="4.376748" name="_OZ3"/>
|
||||
<waypoint lat="51.990657" lon="4.376804" name="_OZ4"/>
|
||||
</waypoints>
|
||||
<sectors>
|
||||
<sector color="red" name="CyberZoo">
|
||||
<corner name="_CZ1"/>
|
||||
<corner name="_CZ2"/>
|
||||
<corner name="_CZ3"/>
|
||||
<corner name="_CZ4"/>
|
||||
</sector>
|
||||
<sector color="#FF9922" name="ObstacleZone">
|
||||
<corner name="_OZ1"/>
|
||||
<corner name="_OZ2"/>
|
||||
<corner name="_OZ3"/>
|
||||
<corner name="_OZ4"/>
|
||||
</sector>
|
||||
</sectors>
|
||||
<exceptions>
|
||||
<exception cond="!InsideCyberZoo(GetPosX(), GetPosY())" deroute="Standby"/>
|
||||
<exception cond="datalink_time > 2" deroute="Land here"/>
|
||||
<exception cond="electrical.bat_low && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land"/>
|
||||
<exception cond="electrical.bat_critical && !(nav_block == IndexOfBlock('Land')) && !(nav_block == IndexOfBlock('Flare')) && !(nav_block == IndexOfBlock('Landed'))" deroute="Land here"/>
|
||||
</exceptions>
|
||||
<blocks>
|
||||
<block name="Wait GPS">
|
||||
<call_once fun="NavKillThrottle()"/>
|
||||
<while cond="!GpsFixValid()"/>
|
||||
</block>
|
||||
<block name="Geo init">
|
||||
<while cond="LessThan(NavBlockTime(), 2)"/>
|
||||
<call_once fun="NavSetAltitudeReferenceHere()"/>
|
||||
</block>
|
||||
<block name="Holding point">
|
||||
<call_once fun="NavKillThrottle()"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
<block key="r" name="Start Engine">
|
||||
<call_once fun="NavResurrect()"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
<block key="t" name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
|
||||
<exception cond="stateGetPositionEnu_f()->z > 1.25" deroute="Standby"/>
|
||||
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
|
||||
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
|
||||
</block>
|
||||
<block key="s" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
|
||||
<stay wp="STDBY"/>
|
||||
</block>
|
||||
<block key="g" name="START" strip_button="Go" strip_icon="lookfore.png">
|
||||
<call_once fun="NavSetWaypointHere(WP_GOAL)"/>
|
||||
</block>
|
||||
<block name="StayGoal">
|
||||
<go wp="GOAL"/>
|
||||
<exception cond="block_time > 1" deroute="MoveGoalForward"/>
|
||||
<exception cond="!safeToGoForwards" deroute="ChangeHeading"/>
|
||||
<exception cond="!InsideObstacleZone(GetPosX(),GetPosY())" deroute="PrepareObstacleRun"/>
|
||||
</block>
|
||||
<block name="MoveGoalForward">
|
||||
<call_once fun="moveWaypointForwards(WP_GOAL,3.0)"/>
|
||||
<deroute block="StayGoal"/>
|
||||
<exception cond="!safeToGoForwards" deroute="ChangeHeading"/>
|
||||
<exception cond="!InsideObstacleZone(WaypointX(WP_GOAL),WaypointY(WP_GOAL))" deroute="PrepareObstacleRun"/>
|
||||
</block>
|
||||
<block name="ChangeHeading">
|
||||
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
|
||||
<while cond="1">
|
||||
<call_once fun="increase_nav_heading(&nav_heading, incrementForAvoidance)"/>
|
||||
<call_once fun="moveWaypointForwards(WP_GOAL,3.0)"/>
|
||||
<go wp="STDBY"/>
|
||||
</while>
|
||||
<exception cond="safeToGoForwards" deroute="StayGoal"/>
|
||||
</block>
|
||||
<block name="PrepareObstacleRun">
|
||||
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
|
||||
<call_once fun="nav_set_heading_towards_waypoint(WP_HOME)"/>
|
||||
<stay wp="STDBY"/>
|
||||
<exception cond="block_time > 1" deroute="GetOutOfObstacleZone"/>
|
||||
</block>
|
||||
<block name="GetOutOfObstacleZone">
|
||||
<call_once fun="moveWaypointForwards(WP_GOAL,0.5)"/>
|
||||
<call_once fun="chooseRandomIncrementAvoidance()"/>
|
||||
<stay wp="GOAL"/>
|
||||
<exception cond="block_time > 1" deroute="START"/>
|
||||
</block>
|
||||
<block key="l" 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>
|
||||
@@ -0,0 +1,144 @@
|
||||
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
|
||||
|
||||
<flight_plan alt="1.0" ground_alt="0" lat0="51.9906224" lon0="4.3767678" max_dist_from_home="8" name="Bebop avoid orange TU Delft Cyberzoo" security_height="0.4">
|
||||
<header>
|
||||
#include "subsystems/datalink/datalink.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "subsystems/radio_control.h"
|
||||
#include "subsystems/ahrs.h"
|
||||
</header>
|
||||
<waypoints>
|
||||
<waypoint lat="51.990631" lon="4.376796" name="HOME"/>
|
||||
<waypoint name="CLIMB" x="1.9" y="1.0"/>
|
||||
<waypoint name="STDBY" x="1.9" y="1.0"/>
|
||||
<waypoint name="TD" x="0.8" y="-1.7"/>
|
||||
<waypoint name="GOAL" x="1.9" y="1.0"/>
|
||||
<waypoint name="TRAJECTORY" x="1.9" y="1.0"/>
|
||||
<waypoint lat="51.9905836" lon="4.3767729" name="_CZ1"/>
|
||||
<waypoint lat="51.9906365" lon="4.3767138" name="_CZ2"/>
|
||||
<waypoint lat="51.990680" lon="4.376805" name="_CZ3"/>
|
||||
<waypoint lat="51.9906226" lon="4.3768699" name="_CZ4"/>
|
||||
<waypoint lat="51.990594" lon="4.376776" name="_OZ1"/>
|
||||
<waypoint lat="51.990636" lon="4.376733" name="_OZ2"/>
|
||||
<waypoint lat="51.990671" lon="4.376806" name="_OZ3"/>
|
||||
<waypoint lat="51.990624" lon="4.376852" name="_OZ4"/>
|
||||
</waypoints>
|
||||
<sectors>
|
||||
<sector color="red" name="CyberZoo">
|
||||
<corner name="_CZ1"/>
|
||||
<corner name="_CZ2"/>
|
||||
<corner name="_CZ3"/>
|
||||
<corner name="_CZ4"/>
|
||||
</sector>
|
||||
<sector color="#FF9922" name="ObstacleZone">
|
||||
<corner name="_OZ1"/>
|
||||
<corner name="_OZ2"/>
|
||||
<corner name="_OZ3"/>
|
||||
<corner name="_OZ4"/>
|
||||
</sector>
|
||||
</sectors>
|
||||
<exceptions>
|
||||
<!-- RC lost -->
|
||||
<exception cond="((radio_control.status == RC_REALLY_LOST) &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Standby"/>
|
||||
<!-- Datalink lost (constant RPM descent) -->
|
||||
<exception cond="((datalink_time > 2) &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Land here"/>
|
||||
<!-- Geofencing XY -->
|
||||
<exception cond="(!InsideCyberZoo(GetPosX(), GetPosY()) &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Land here"/>
|
||||
<!-- Geofencing Z 2.5 -->
|
||||
<exception cond="((GetPosAlt() > 3.5) &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Land here"/>
|
||||
<!-- Geofencing Z 4.5 (constant RPM descent)-->
|
||||
<exception cond="((GetPosAlt() > 4.5) &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
(autopilot_in_flight == true) )" deroute="Landed"/>
|
||||
<!-- Bat low -->
|
||||
<exception cond="(electrical.bat_low &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Land here"/>
|
||||
<!-- Bat critical (constant RPM no stabilization)-->
|
||||
<exception cond="(electrical.bat_critical &&
|
||||
!(IndexOfBlock('Holding point') > nav_block) &&
|
||||
!(nav_block >= IndexOfBlock('Land here')) &&
|
||||
(autopilot_in_flight == true) )" deroute="Land here"/>
|
||||
</exceptions>
|
||||
<blocks>
|
||||
<block name="Wait GPS">
|
||||
<call_once fun="NavKillThrottle()"/>
|
||||
<while cond="!GpsFixValid()"/>
|
||||
</block>
|
||||
<block name="Geo init">
|
||||
<while cond="LessThan(NavBlockTime(), 2)"/>
|
||||
<call_once fun="NavSetAltitudeReferenceHere()"/>
|
||||
</block>
|
||||
<block name="Holding point">
|
||||
<call_once fun="NavKillThrottle()"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
</block>
|
||||
<block key="r" name="Start Engine">
|
||||
<call_once fun="NavResurrect()"/>
|
||||
<attitude pitch="0" roll="0" throttle="0" until="FALSE" vmode="throttle"/>
|
||||
<call_once fun="NavResurrect()"/>
|
||||
</block>
|
||||
<block key="t" name="Takeoff" strip_button="Takeoff" strip_icon="takeoff.png">
|
||||
<exception cond="GetPosAlt() > 1.0" deroute="Standby"/>
|
||||
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
|
||||
<stay climb="nav_climb_vspeed" vmode="climb" wp="CLIMB"/>
|
||||
</block>
|
||||
<block key="s" name="Standby" strip_button="Standby" strip_icon="home.png">
|
||||
<call_once fun="NavSetWaypointHere(WP_STDBY)"/>
|
||||
<stay wp="STDBY"/>
|
||||
</block>
|
||||
<block key="g" name="START" strip_button="Go" strip_icon="lookfore.png">
|
||||
<call_once fun="NavSetWaypointHere(WP_GOAL)"/>
|
||||
<set var="trajectoryConfidence" value="1"/>
|
||||
</block>
|
||||
<block name="StayGoal">
|
||||
<stay wp="GOAL"/>
|
||||
<exception cond="!InsideObstacleZone(WaypointX(WP_TRAJECTORY),WaypointY(WP_TRAJECTORY))" deroute="PrepareObstacleRun"/>
|
||||
</block>
|
||||
<block name="PrepareObstacleRun">
|
||||
<while cond="!InsideObstacleZone(WaypointX(WP_TRAJECTORY),WaypointY(WP_TRAJECTORY))">
|
||||
<call_once fun="increase_nav_heading(&nav_heading, 5)"/>
|
||||
</while>
|
||||
</block>
|
||||
<block name="GetIntoObstacleZone">
|
||||
<while cond="!InsideObstacleZone(GetPosX(),GetPosY())">
|
||||
<call_once fun="moveWaypointForward(WP_GOAL, 0.1)"/>
|
||||
<go wp="GOAL"/>
|
||||
</while>
|
||||
<deroute block="START"/>
|
||||
</block>
|
||||
<block key="l" name="Land here" strip_button="Land Here" strip_icon="land-right.png">
|
||||
<call_once fun="NavSetWaypointHere(WP_TD)"/>
|
||||
<go wp="TD"/>
|
||||
<deroute block="Flare"/>
|
||||
</block>
|
||||
<block name="Land">
|
||||
<go wp="TD"/>
|
||||
<deroute block="Flare"/>
|
||||
</block>
|
||||
<block name="Flare">
|
||||
<exception cond="NavDetectGround()" deroute="Holding point"/>
|
||||
<exception cond="!nav_is_in_flight()" deroute="Landed"/>
|
||||
<exception cond="0.10 > GetPosAlt()" 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>
|
||||
@@ -5,7 +5,7 @@
|
||||
<description>
|
||||
Avoid all objects that are orange!
|
||||
This example module shows how you can use the camera stream and colorfilter to detect orange objects.
|
||||
By adding this module to your flightplan and flying in the cyberzoo with the flightplan tudelft/course2016_avoid_orange_cyberzoo.xml you will avoid every obstacle that is orange.
|
||||
By adding this module to your flightplan and flying in the cyberzoo with the flightplan tudelft/course2017_avoid_orange_cyberzoo.xml you will avoid every obstacle that is orange.
|
||||
</description>
|
||||
</doc>
|
||||
<depends>cv_colorfilter.xml</depends>
|
||||
|
||||
@@ -0,0 +1,14 @@
|
||||
<conf>
|
||||
<aircraft
|
||||
name="bebop_avoid"
|
||||
ac_id="42"
|
||||
airframe="airframes/tudelft/bebop_orangeavoid_course2017.xml"
|
||||
radio="radios/dummy.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/tudelft/course2017_avoid_orange_cyberzoo.xml"
|
||||
settings="settings/rotorcraft_basic.xml"
|
||||
settings_modules="modules/video_rtp_stream.xml modules/cv_colorfilter.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="white"
|
||||
release="b740eb6e6f3843316778ffe3c7582ce0631e5411"
|
||||
/>
|
||||
</conf>
|
||||
@@ -0,0 +1,63 @@
|
||||
<control_panel name="paparazzi control panel">
|
||||
<section name="programs">
|
||||
<program name="Server" command="sw/ground_segment/tmtc/server"/>
|
||||
<program name="Data Link" command="sw/ground_segment/tmtc/link">
|
||||
<arg flag="-d" constant="/dev/ttyUSB0"/>
|
||||
</program>
|
||||
<program name="GCS" command="sw/ground_segment/cockpit/gcs"/>
|
||||
<program name="Bebop Video Stream" command="/usr/bin/cvlc ftp://192.168.42.1/internal_000/stream.sdp --avcodec-hw=vaapi --no-xlib --quiet --no-interact"/>
|
||||
<program name="Messages" command="sw/ground_segment/tmtc/messages"/>
|
||||
<program name="Settings" command="sw/ground_segment/tmtc/settings">
|
||||
<arg flag="-ac" constant="@AIRCRAFT"/>
|
||||
</program>
|
||||
<program name="Log Plotter" command="sw/logalizer/logplotter"/>
|
||||
<program name="Real-time Plotter" command="sw/logalizer/plotter"/>
|
||||
<program name="Log File Player" command="sw/logalizer/play"/>
|
||||
<program name="Simulator" command="sw/simulator/pprzsim-launch"/>
|
||||
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
|
||||
<arg flag="-ac" constant="@AIRCRAFT"/>
|
||||
<arg flag="hobbyking.xml"/>
|
||||
</program>
|
||||
<program name="Environment Simulator" command="sw/simulator/gaia"/>
|
||||
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy"/>
|
||||
</section>
|
||||
<section name="sessions">
|
||||
<session name="Bebop basic">
|
||||
<program name="Data Link">
|
||||
<arg flag="-udp"/>
|
||||
</program>
|
||||
<program name="Server"/>
|
||||
<program name="GCS">
|
||||
<arg flag="-speech"/>
|
||||
</program>
|
||||
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
|
||||
<arg flag="-ac" constant="@AIRCRAFT"/>
|
||||
<arg flag="hobbyking.xml"/>
|
||||
</program>
|
||||
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy">
|
||||
<arg flag="-ac 9999" constant="@AC_ID"/>
|
||||
</program>
|
||||
<program name="Bebop Video Stream"/>
|
||||
</session>
|
||||
<session name="Bebop extensive">
|
||||
<program name="Data Link">
|
||||
<arg flag="-udp"/>
|
||||
</program>
|
||||
<program name="Server"/>
|
||||
<program name="GCS">
|
||||
<arg flag="-speech"/>
|
||||
</program>
|
||||
<program name="Joystick" command="sw/ground_segment/joystick/input2ivy">
|
||||
<arg flag="-d" constant="2"/>
|
||||
<arg flag="-ac" constant="@AIRCRAFT"/>
|
||||
<arg flag="hobbyking.xml"/>
|
||||
</program>
|
||||
<program name="NatNet" command="sw/ground_segment/misc/natnet2ivy">
|
||||
<arg flag="-ac 3" constant="@AC_ID"/>
|
||||
</program>
|
||||
|
||||
<program name="Messages" command="sw/ground_segment/tmtc/messages"/>
|
||||
</session>
|
||||
|
||||
</section>
|
||||
</control_panel>
|
||||
@@ -13,76 +13,143 @@
|
||||
#include "modules/orange_avoider/orange_avoider.h"
|
||||
#include "modules/computer_vision/colorfilter.h"
|
||||
#include "firmwares/rotorcraft/navigation.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "state.h"
|
||||
#include <time.h>
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
uint8_t safeToGoForwards = false;
|
||||
int tresholdColorCount = 200;
|
||||
int32_t incrementForAvoidance;
|
||||
|
||||
#define ORANGE_AVOIDER_VERBOSE TRUE
|
||||
|
||||
#define PRINT(string,...) fprintf(stderr, "[orange_avoider->%s()] " string,__FUNCTION__ , ##__VA_ARGS__)
|
||||
#if ORANGE_AVOIDER_VERBOSE
|
||||
#define VERBOSE_PRINT PRINT
|
||||
#else
|
||||
#define VERBOSE_PRINT(...)
|
||||
#endif
|
||||
|
||||
uint8_t safeToGoForwards = false;
|
||||
int tresholdColorCount = 0.05 * 124800; // 520 x 240 = 124.800 total pixels
|
||||
float incrementForAvoidance;
|
||||
uint16_t trajectoryConfidence = 1;
|
||||
float maxDistance = 2.25;
|
||||
|
||||
/*
|
||||
* Initialisation function, setting the colour filter, random seed and incrementForAvoidance
|
||||
*/
|
||||
void orange_avoider_init()
|
||||
{
|
||||
// Initialise the variables of the colorfilter to accept orange
|
||||
color_lum_min = 0;
|
||||
color_lum_max = 131;
|
||||
color_cb_min = 93;
|
||||
color_cb_max = 255;
|
||||
color_cr_min = 134;
|
||||
color_cr_max = 255;
|
||||
color_lum_min = 20;
|
||||
color_lum_max = 255;
|
||||
color_cb_min = 75;
|
||||
color_cb_max = 145;
|
||||
color_cr_min = 167;
|
||||
color_cr_max = 255;
|
||||
// Initialise random values
|
||||
srand(time(NULL));
|
||||
chooseRandomIncrementAvoidance();
|
||||
}
|
||||
|
||||
/*
|
||||
* Function that checks it is safe to move forwards, and then moves a waypoint forward or changes the heading
|
||||
*/
|
||||
void orange_avoider_periodic()
|
||||
{
|
||||
// Check the amount of orange. If this is above a threshold
|
||||
// you want to turn a certain amount of degrees
|
||||
safeToGoForwards = color_count < tresholdColorCount;
|
||||
printf("Checking if this function is called %d threshold: %d now: %d \n", color_count, tresholdColorCount,
|
||||
safeToGoForwards);
|
||||
VERBOSE_PRINT("Color_count: %d threshold: %d safe: %d \n", color_count, tresholdColorCount, safeToGoForwards);
|
||||
float moveDistance = fmin(maxDistance, 0.05 * trajectoryConfidence);
|
||||
if (safeToGoForwards) {
|
||||
moveWaypointForward(WP_GOAL, moveDistance);
|
||||
moveWaypointForward(WP_TRAJECTORY, 1.25 * moveDistance);
|
||||
nav_set_heading_towards_waypoint(WP_GOAL);
|
||||
chooseRandomIncrementAvoidance();
|
||||
trajectoryConfidence += 1;
|
||||
} else {
|
||||
waypoint_set_here_2d(WP_GOAL);
|
||||
waypoint_set_here_2d(WP_TRAJECTORY);
|
||||
increase_nav_heading(&nav_heading, incrementForAvoidance);
|
||||
if (trajectoryConfidence > 5) {
|
||||
trajectoryConfidence -= 4;
|
||||
} else {
|
||||
trajectoryConfidence = 1;
|
||||
}
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
/*
|
||||
* Increases the NAV heading. Assumes heading is an INT32_ANGLE. It is bound in this function.
|
||||
*/
|
||||
uint8_t increase_nav_heading(int32_t *heading, int32_t increment)
|
||||
uint8_t increase_nav_heading(int32_t *heading, float incrementDegrees)
|
||||
{
|
||||
*heading = *heading + increment;
|
||||
struct Int32Eulers *eulerAngles = stateGetNedToBodyEulers_i();
|
||||
int32_t newHeading = eulerAngles->psi + ANGLE_BFP_OF_REAL(RadOfDeg(incrementDegrees));
|
||||
// Check if your turn made it go out of bounds...
|
||||
INT32_ANGLE_NORMALIZE(*heading); // HEADING HAS INT32_ANGLE_FRAC....
|
||||
INT32_ANGLE_NORMALIZE(newHeading); // HEADING HAS INT32_ANGLE_FRAC....
|
||||
*heading = newHeading;
|
||||
VERBOSE_PRINT("Increasing heading to %f\n", DegOfRad(ANGLE_FLOAT_OF_BFP(*heading));
|
||||
return false;
|
||||
}
|
||||
uint8_t moveWaypointForwards(uint8_t waypoint, float distanceMeters)
|
||||
|
||||
/*
|
||||
* Calculates coordinates of a distance of 'distanceMeters' forward w.r.t. current position and heading
|
||||
*/
|
||||
static uint8_t calculateForwards(struct EnuCoor_i *new_coor, float distanceMeters)
|
||||
{
|
||||
struct EnuCoor_i *pos = stateGetPositionEnu_i(); // Get your current position
|
||||
struct Int32Eulers *eulerAngles = stateGetNedToBodyEulers_i();
|
||||
// Calculate the sine and cosine of the heading the drone is keeping
|
||||
float sin_heading = sinf(ANGLE_FLOAT_OF_BFP(eulerAngles->psi));
|
||||
float cos_heading = cosf(ANGLE_FLOAT_OF_BFP(eulerAngles->psi));
|
||||
// Now determine where to place the waypoint you want to go to
|
||||
new_coor->x = pos->x + POS_BFP_OF_REAL(sin_heading * (distanceMeters));
|
||||
new_coor->y = pos->y + POS_BFP_OF_REAL(cos_heading * (distanceMeters));
|
||||
VERBOSE_PRINT("Calculated %f m forward position. x: %f y: %f based on pos(%f, %f) and heading(%f)\n", distanceMeters,
|
||||
POS_FLOAT_OF_BFP(new_coor->x), POS_FLOAT_OF_BFP(new_coor->y), POS_FLOAT_OF_BFP(pos->x), POS_FLOAT_OF_BFP(pos->y),
|
||||
DegOfRad(ANGLE_FLOAT_OF_BFP(eulerAngles->psi));
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
* Sets waypoint 'waypoint' to the coordinates of 'new_coor'
|
||||
*/
|
||||
uint8_t moveWaypoint(uint8_t waypoint, struct EnuCoor_i *new_coor)
|
||||
{
|
||||
VERBOSE_PRINT("Moving waypoint %d to x:%f y:%f\n", waypoint, POS_FLOAT_OF_BFP(new_coor->x),
|
||||
POS_FLOAT_OF_BFP(new_coor->y));
|
||||
waypoint_set_xy_i(waypoint, new_coor->x, new_coor->y);
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculates coordinates of distance forward and sets waypoint 'waypoint' to those coordinates
|
||||
*/
|
||||
uint8_t moveWaypointForward(uint8_t waypoint, float distanceMeters)
|
||||
{
|
||||
struct EnuCoor_i new_coor;
|
||||
struct EnuCoor_i *pos = stateGetPositionEnu_i(); // Get your current position
|
||||
|
||||
// Calculate the sine and cosine of the heading the drone is keeping
|
||||
float sin_heading = sinf(ANGLE_FLOAT_OF_BFP(nav_heading));
|
||||
float cos_heading = cosf(ANGLE_FLOAT_OF_BFP(nav_heading));
|
||||
|
||||
// Now determine where to place the waypoint you want to go to
|
||||
new_coor.x = pos->x + POS_BFP_OF_REAL(sin_heading * (distanceMeters));
|
||||
new_coor.y = pos->y + POS_BFP_OF_REAL(cos_heading * (distanceMeters));
|
||||
new_coor.z = pos->z; // Keep the height the same
|
||||
|
||||
// Set the waypoint to the calculated position
|
||||
waypoint_set_xy_i(waypoint, new_coor.x, new_coor.y);
|
||||
|
||||
calculateForwards(&new_coor, distanceMeters);
|
||||
moveWaypoint(waypoint, &new_coor);
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
* Sets the variable 'incrementForAvoidance' randomly positive/negative
|
||||
*/
|
||||
uint8_t chooseRandomIncrementAvoidance()
|
||||
{
|
||||
|
||||
// Randomly choose CW or CCW avoiding direction
|
||||
int r = rand() % 2;
|
||||
if (r == 0) {
|
||||
incrementForAvoidance = 350;
|
||||
incrementForAvoidance = 10.0;
|
||||
VERBOSE_PRINT("Set avoidance increment to: %f\n", incrementForAvoidance);
|
||||
} else {
|
||||
incrementForAvoidance = -350;
|
||||
incrementForAvoidance = -10.0;
|
||||
VERBOSE_PRINT("Set avoidance increment to: %f\n", incrementForAvoidance);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -13,13 +13,16 @@
|
||||
#ifndef ORANGE_AVOIDER_H
|
||||
#define ORANGE_AVOIDER_H
|
||||
#include <inttypes.h>
|
||||
#include "math/pprz_geodetic_int.h"
|
||||
|
||||
extern uint8_t safeToGoForwards;
|
||||
extern int32_t incrementForAvoidance;
|
||||
extern float incrementForAvoidance;
|
||||
extern uint16_t trajectoryConfidence;
|
||||
extern void orange_avoider_init(void);
|
||||
extern void orange_avoider_periodic(void);
|
||||
extern uint8_t moveWaypointForwards(uint8_t waypoint, float distanceMeters);
|
||||
extern uint8_t increase_nav_heading(int32_t *heading, int32_t increment);
|
||||
extern uint8_t moveWaypointForward(uint8_t waypoint, float distanceMeters);
|
||||
extern uint8_t moveWaypoint(uint8_t waypoint, struct EnuCoor_i *new_coor);
|
||||
extern uint8_t increase_nav_heading(int32_t *heading, float incrementDegrees);
|
||||
extern uint8_t chooseRandomIncrementAvoidance(void);
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user