Merge pull request #2137 from EwoudSmeur/fan_demo_branch

INDI settings and fan demo
This commit is contained in:
Ewoud Smeur
2017-10-25 10:29:32 +02:00
committed by GitHub
6 changed files with 298 additions and 7 deletions
+11
View File
@@ -98,6 +98,17 @@
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"
gui_color="#ffffcccaccca"
/>
<aircraft
name="fan_demo"
ac_id="28"
airframe="airframes/TUDELFT/tudelft_bebop_indi_actuators.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/TUDELFT/fan_demo.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/air_data.xml [modules/geo_mag.xml] modules/guidance_indi.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffcccaccca"
/>
<aircraft
name="Bebop_actuators"
ac_id="24"
+191
View File
@@ -0,0 +1,191 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="bebop_indi">
<firmware name="rotorcraft">
<target name="ap" board="bebop"/>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="udp"/>
</target>
<!--define name="USE_SONAR" value="TRUE"/-->
<!-- Subsystem section -->
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="datalink"/>
<module name="stabilization" type="indi">
<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"/>
<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-->
</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="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>
<command_laws>
<set servo="TOP_LEFT" value="autopilot_get_motors_on() ? actuators_pprz[0] : -MAX_PPRZ"/>
<set servo="TOP_RIGHT" value="autopilot_get_motors_on() ? actuators_pprz[1] : -MAX_PPRZ"/>
<set servo="BOTTOM_RIGHT" value="autopilot_get_motors_on() ? actuators_pprz[2] : -MAX_PPRZ"/>
<set servo="BOTTOM_LEFT" value="autopilot_get_motors_on() ? actuators_pprz[3] : -MAX_PPRZ"/>
</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>
<include href="conf/airframes/TUDELFT/calibrations/bebop7.xml" />
<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"/>
<!-- For vibrating airfames -->
<define name="GRAVITY_HEURISTIC_FACTOR" value="0"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
</section>
<section name="GUIDANCE_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="FALSE"/>
<define name="GUIDANCE_INDI_POS_GAIN" value="0.7"/>
<define name="GUIDANCE_INDI_SPEED_GAIN" value="1.5"/>
</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="400" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<define name="G1_ROLL" value="{20 , -20, -20 , 20 }"/>
<define name="G1_PITCH" value="{14 , 14, -14 , -14 }"/>
<define name="G1_YAW" value="{-1, 1, -1, 1}"/>
<define name="G1_THRUST" value="{-.4, -.4, -.4, -.4}"/>
<!--Counter torque effect of spinning up a rotor-->
<define name="G2" value="{-61.2093, 65.3670, -65.7419, 65.4516}"/>
<!-- 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"/>
<define name="ESTIMATION_FILT_CUTOFF" value="4.0"/>
<define name="FILT_CUTOFF" value="5.0"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN" value="{0.1, 0.1, 0.1, 0.1}"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="TRUE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="700"/>
<define name="HOVER_KD" value="200"/>
<define name="HOVER_KI" value="400"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.63"/>
<define name="ADAPT_THROTTLE_ENABLED" value="FALSE"/>
</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"/>
<define name="USE_REF" value="FALSE"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="130"/>
<define name="DGAIN" value="200"/>
<define name="IGAIN" value="70"/>
</section>
<section name="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="2.5"/>
<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="bebop" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
<define name="NO_MOTOR_MIXING" value="TRUE"/>
</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="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>
+77
View File
@@ -0,0 +1,77 @@
<!DOCTYPE flight_plan SYSTEM "../flight_plan.dtd">
<flight_plan alt="0.4" ground_alt="0" lat0="51.990634" lon0="4.376789" max_dist_from_home="20" name="Rotorcraft Optitrack (Delft)" security_height="0.2">
<header>
#include "autopilot.h"
</header>
<waypoints>
<waypoint name="HOME" x="0.0" y="0.0"/>
<waypoint name="CLIMB" x="1.2" y="-0.6"/>
<waypoint name="GOAL" x="2.0" y="2.0"/>
<waypoint name="STDBY" x="-0.7" y="-0.8"/>
<waypoint name="TD" x="-0.9" y="0.0"/>
<waypoint lat="51.990620" lon="4.376805" name="p1"/>
<waypoint lat="51.990611" lon="4.376783" name="p2"/>
<waypoint lat="51.9906213" lon="4.3768628" name="FA1"/>
<waypoint lat="51.9905874" lon="4.3767766" name="FA2"/>
<waypoint lat="51.9906409" lon="4.3767226" name="FA3"/>
<waypoint lat="51.9906737" lon="4.3768074" name="FA4"/>
</waypoints>
<sectors>
<sector color="red" name="Flight_Area">
<corner name="FA4"/>
<corner name="FA3"/>
<corner name="FA2"/>
<corner name="FA1"/>
</sector>
</sectors>
<blocks>
<block name="Wait GPS">
<call_once fun="NavKillThrottle()"/>
<while cond="!GpsFixValid()"/>
</block>
<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 > 0.3" deroute="Standby"/>
<call_once fun="NavSetWaypointHere(WP_CLIMB)"/>
<stay wp="CLIMB"/>
</block>
<block name="Standby" strip_button="Standby" strip_icon="home.png">
<stay wp="STDBY"/>
</block>
<block name="stay_p1">
<call_once fun="nav_set_heading_deg(-30)"/>
<stay until="stage_time>3" wp="p1"/>
</block>
<block name="line_p1_p2">
<go from="p1" hmode="route" wp="p2"/>
<stay until="stage_time>10" wp="p2"/>
<go from="p2" hmode="route" wp="p1"/>
<stay until="stage_time>10" wp="p1"/>
<deroute block="line_p1_p2"/>
</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>
+8
View File
@@ -6,6 +6,14 @@
Guidance controller for rotorcraft using INDI
</description>
</doc>
<settings>
<dl_settings>
<dl_settings NAME="guidance_indi">
<dl_setting var="guidance_indi_pos_gain" min="0" step="0.1" max="10.0" shortname="kp_p" param="GUIDANCE_INDI_POS_GAIN" persistent="true"/>
<dl_setting var="guidance_indi_speed_gain" min="0" step="0.1" max="10.0" shortname="kp_p" param="GUIDANCE_INDI_SPEED_GAIN" persistent="true"/>
</dl_settings>
</dl_settings>
</settings>
<header>
<file name="guidance_indi.h"/>
</header>
+7 -7
View File
@@ -37,13 +37,13 @@
<settings>
<dl_settings>
<dl_settings NAME="indi">
<dl_setting var="reference_acceleration.err_p" min="0" step="1" max="2500" shortname="kp_p" param="STABILIZATION_INDI_REF_ERR_P" persistent="true"/>
<dl_setting var="reference_acceleration.rate_p" min="0" step="0.1" max="100" shortname="kd_p" param="STABILIZATION_INDI_REF_RATE_P" persistent="true"/>
<dl_setting var="reference_acceleration.err_q" min="0" step="1" max="2500" shortname="kp_q" param="STABILIZATION_INDI_REF_ERR_Q" persistent="true"/>
<dl_setting var="reference_acceleration.rate_q" min="0" step="0.1" max="100" shortname="kd_q" param="STABILIZATION_INDI_REF_RATE_P" persistent="true"/>
<dl_setting var="reference_acceleration.err_r" min="0" step="1" max="2500" shortname="kp_r" param="STABILIZATION_INDI_REF_ERR_R" persistent="true"/>
<dl_setting var="reference_acceleration.rate_r" min="0" step="0.1" max="100" shortname="kd_r" param="STABILIZATION_INDI_REF_RATE_P" persistent="true"/>
<dl_setting var="indi_use_adaptive" min="0" step="1" max="1" shortname="use_adaptive" values="FALSE|TRUE" param="STABILIZATION_INDI_USE_ADAPTIVE" type="uint8" persistent="true"/>
<dl_setting var="reference_acceleration.err_p" min="0" step="1" max="2500" shortname="kp_p" param="STABILIZATION_INDI_REF_ERR_P"/>
<dl_setting var="reference_acceleration.rate_p" min="0" step="0.1" max="100" shortname="kd_p" param="STABILIZATION_INDI_REF_RATE_P"/>
<dl_setting var="reference_acceleration.err_q" min="0" step="1" max="2500" shortname="kp_q" param="STABILIZATION_INDI_REF_ERR_Q"/>
<dl_setting var="reference_acceleration.rate_q" min="0" step="0.1" max="100" shortname="kd_q" param="STABILIZATION_INDI_REF_RATE_P"/>
<dl_setting var="reference_acceleration.err_r" min="0" step="1" max="2500" shortname="kp_r" param="STABILIZATION_INDI_REF_ERR_R"/>
<dl_setting var="reference_acceleration.rate_r" min="0" step="0.1" max="100" shortname="kd_r" param="STABILIZATION_INDI_REF_RATE_P"/>
<dl_setting var="indi_use_adaptive" min="0" step="1" max="1" shortname="use_adaptive" values="FALSE|TRUE" param="STABILIZATION_INDI_USE_ADAPTIVE" type="uint8"/>
</dl_settings>
</dl_settings>
</settings>
@@ -41,4 +41,8 @@ extern void stabilization_attitude_set_setpoint_rp_quat_f(struct FloatEulers* in
extern float guidance_indi_thrust_specific_force_gain;
extern struct FloatVect3 euler_cmd;
// settings for guidance INDI
extern float guidance_indi_pos_gain;
extern float guidance_indi_speed_gain;
#endif /* GUIDANCE_INDI_H */