You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
101 lines
4.3 KiB
101 lines
4.3 KiB
<?xml version="1.0"?> |
|
<?xml-stylesheet type="text/xsl" href="http://gtri.gatech.edu"?> |
|
<runscript xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" |
|
name="Straight flying"> |
|
|
|
<!-- <run start="0.0" end="100" dt="0.00833333" --> |
|
<run start="0.0" end="10000000" dt="0.001" |
|
{% if plane %} |
|
motion_multiplier="1" |
|
{% endif %} |
|
time_warp="1" |
|
enable_gui="true" |
|
network_gui="false" |
|
start_paused="false"/> |
|
|
|
<stream_port>50051</stream_port> |
|
<stream_ip>localhost</stream_ip> |
|
|
|
<end_condition>all_dead</end_condition> <!-- time, one_team, none--> |
|
|
|
<grid_spacing>10</grid_spacing> |
|
<grid_size>1000</grid_size> |
|
|
|
<terrain>{% if terrain %}{{ terrain }}{% else %}mcmillan{% endif %}</terrain> |
|
<background_color>191 191 191</background_color> <!-- Red Green Blue --> |
|
<gui_update_period>10</gui_update_period> <!-- milliseconds --> |
|
|
|
<plot_tracks>false</plot_tracks> |
|
<output_type>all</output_type> |
|
<show_plugins>false</show_plugins> |
|
|
|
<metrics>SimpleCollisionMetrics</metrics> |
|
|
|
<log_dir>~/.scrimmage/logs</log_dir> |
|
|
|
{% if plane %} |
|
<latitude_origin>{% if lat %}{{ lat }}{% else %}32.42553{% endif %}</latitude_origin> |
|
<longitude_origin>{% if lon %}{{ lon }}{% else %}-84.79109{% endif %}</longitude_origin> |
|
<altitude_origin>{% if alt %}{{ alt }}{% else %}75{% endif %}</altitude_origin> |
|
{% else %} |
|
<latitude_origin>{% if lat %}{{ lat }}{% else %}34.458281{% endif %}</latitude_origin> |
|
<longitude_origin>{% if lon %}{{ lon }}{% else %}-84.180209{% endif %}</longitude_origin> |
|
<altitude_origin>{% if alt %}{{ alt }}{% else %}450{% endif %}</altitude_origin> |
|
{% endif %} |
|
|
|
<show_origin>true</show_origin> |
|
<origin_length>10</origin_length> |
|
|
|
<network>LocalNetwork</network> |
|
<network>GlobalNetwork</network> |
|
|
|
<entity_interaction>SimpleCollision</entity_interaction> |
|
<entity_interaction enable_startup_collisions="false" |
|
remove_on_collision="false">GroundCollision</entity_interaction> |
|
|
|
<!-- uncomment "seed" and use integer for deterministic results --> |
|
<!--<seed>2147483648</seed>--> |
|
|
|
<!-- ========================== TEAM 1 ========================= --> |
|
{% for e in entities %} |
|
<entity> |
|
<team_id>1</team_id> |
|
<color>77 77 255</color> |
|
<count>1</count> |
|
<health>1</health> |
|
<radius>1</radius> |
|
|
|
<x>{% if e.x %}{{ e.x }}{% else %}0{% endif %}</x> |
|
<y>{% if e.y %}{{ e.y }}{% else %}0{% endif %}</y> |
|
<z>{% if e.z %}{{ e.z }}{% else %}0{% endif %}</z> |
|
{% if plane %}<pitch>-20</pitch>{% endif %} |
|
<heading>{% if e.heading %}{{ e.heading }}{% else %}0{% endif %}</heading> |
|
|
|
|
|
<sensor>RigidBody6DOFStateSensor</sensor> |
|
<controller>DirectController</controller> |
|
|
|
<!-- Use this settings in SITL --> |
|
<autonomy to_ardupilot_port="{% if e.to_ardupilot_port %}{{ e.to_ardupilot_port }}{% else %}9003{% endif %}" |
|
from_ardupilot_port="{% if e.from_ardupilot_port %}{{ e.from_ardupilot_port }}{% else %}9002{% endif %}" |
|
to_ardupilot_ip="{% if e.to_ardupilot_ip %}{{ e.to_ardupilot_ip }}{% else %}127.0.0.1{% endif %}" |
|
{% if plane %} |
|
>ArduPilot</autonomy> |
|
<!-- Use this settings in HIL through mavproxy --> |
|
<!-- <autonomy to_ardupilot_port="5501" from_ardupilot_port="5502" mavproxy_mode="true">ArduPilot</autonomy> --> |
|
<!-- <motion_model drawVel="0" drawAngVel="0" drawAcc="0" use_launcher="1" launch_time="60" launch_accel="200">${motion_model=JSBSimControl}</motion_model> --> |
|
<motion_model drawVel="0" drawAngVel="0" drawAcc="0">{% if e.motion_model %}{{ e.motion_model }}{% else %}JSBSimControl{% endif %}</motion_model> |
|
<script_name>rascal_no_autopilot.xml</script_name> |
|
<visual_model>{% if e.visual_model %}{{ e.visual_model }}{% else %}zephyr-blue{% endif %}</visual_model> |
|
{% else %} |
|
servo_map="[ motor_0 0 1000 +2000 346.41 1200.0 +1 ] |
|
[ motor_1 1 1000 +2000 346.41 1200.0 +1 ] |
|
[ motor_2 2 1000 +2000 346.41 1200.0 +1 ] |
|
[ motor_3 3 1000 +2000 346.41 1200.0 +1 ]" |
|
>ArduPilot</autonomy> |
|
<motion_model write_csv="true">{% if e.motion_model %}{{ e.motion_model }}{% else %}Multirotor{% endif %}</motion_model> |
|
<visual_model>{% if e.visual_model %}{{ e.visual_model }}{% else %}iris{% endif %}</visual_model> |
|
{% endif %} |
|
</entity> |
|
{% endfor %} |
|
</runscript>
|
|
|