Skip to content

Commit

Permalink
added maps3
Browse files Browse the repository at this point in the history
  • Loading branch information
anchobi-no committed Feb 18, 2021
1 parent 590be0f commit 4afd268
Show file tree
Hide file tree
Showing 6 changed files with 60 additions and 10 deletions.
10 changes: 7 additions & 3 deletions ai_race/sim_environment/launch/sim_environment.launch
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,13 @@
<arg name="arrow" value="$(arg arrow)" />
<arg name="record" value="$(arg record)" />
<arg name="play" value="$(arg play)" />
<arg name="robot_pos" value="-x 1.8 -y 0.6 -z 0.03 -Y 0.0"/>
<arg name="camera_pos" value="-x 2.0 -y 0.12 -z 0.13 -Y 1.57"/>
<arg name="godeye_pos" value="-x 3.3 -y 2.3 -z 0.0 -Y 1.57"/>
</include>
</group>

<!-- level s (if you want to run , set launch arg level=s -->
<!-- level l (if you want to run , set launch arg level=s -->
<group if="$(eval level=='l')">
<include file="$(find sim_environment)/launch/wheel_robot_with_surveillance.launch">
<arg name="track_name" value="medium_track_plane_w_wall_large.world" />
Expand All @@ -88,8 +91,9 @@
<arg name="arrow" value="$(arg arrow)" />
<arg name="record" value="$(arg record)" />
<arg name="play" value="$(arg play)" />
<arg name="robot_x_pos" value="5.75"/>
<arg name="camera_x_pos" value="5.15"/>
<arg name="robot_pos" value="-x 5.75 -y 0 -z 0 -Y 1.57"/>
<arg name="camera_pos" value="-x 5.15 -y 0 -z 0 -Y 0.0"/>
<arg name="godeye_pos" value="-x 0 -y 0 -z 4.0 -Y 0.0"/>
<arg name="perspective" value="3" />
</include>
</group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,9 @@
<arg name="record" default="false" />
<arg name="play" default="false" />
<arg name="perspective" default="1" />
<arg name="robot_x_pos" default="1.6" />
<arg name="camera_x_pos" default="1.0" />
<arg name="robot_pos" default="-x 1.6 -y 0 -z 0 -Y 1.57" />
<arg name="camera_pos" default="-x 1.0 -y 0 -z 0 -Y 0" />
<arg name="godeye_pos" default="-x 0 -y 0 -z 0 -Y 0" />

<!-- We resume the logic in empty_world.launch, changing only the name of
the world to be launched -->
Expand Down Expand Up @@ -43,11 +44,11 @@

<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="wheel_robot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -x $(arg robot_x_pos) -y 0.0 -z 0.0 -Y 1.57 -param robot_description -model wheel_robot" />
args="-urdf $(arg robot_pos) -param robot_description -model wheel_robot" />
<node name="camera_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -x $(arg camera_x_pos) -y 0.0 -z 0.0 -Y 0 -param camera_description -model surveillance_camera" />
args="-urdf $(arg camera_pos) -param camera_description -model surveillance_camera" />
<node name="godeye_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -x 0.0 -y 0.0 -z 0.0 -param godeye_description -model godeye_camera" />
args="-urdf $(arg godeye_pos) -param godeye_description -model godeye_camera" />
<group if="$(eval perspective==1)">
<node name="godeye_perspective_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -x 2.5 -y -3.5 -z 0.0 -param godeye_perspective_description -model godeye_camera_perspective" />
Expand All @@ -58,7 +59,7 @@
</group>
<group if="$(eval perspective==3)">
<node name="godeye_perspective_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -x 8 -y -11.5 -z 0.0 -param godeye_perspective_description -model godeye_camera_perspective" />
args="-urdf -x 7.5 -y -10.5 -z 0.0 -param godeye_perspective_description -model godeye_camera_perspective" />
</group>

<!-- robot visualization in Rviz -->
Expand Down
1 change: 1 addition & 0 deletions ai_race/sim_environment/urdf/godeye.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" />
<static>true</static>
</gazebo>


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@
</joint>

<!-- camera -->
<camera_macro_perspective2_720x480 parent="base_link" prefix="godeye_camera_perspective" xyz="-4.5 0.0 0" x_rot="0" y_rot="-150" z_rot="-38"/>
<camera_macro_perspective_720x480 parent="base_link" prefix="godeye_camera_perspective" xyz="-4.0 0.0 0" x_rot="0" y_rot="-160" z_rot="-41"/>

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" />
<static>true</static>
</gazebo>


Expand Down
43 changes: 43 additions & 0 deletions ai_race/sim_world/worlds/medium_track_plane_w_wall_large.world
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,49 @@
<pose>0 0 0 0 0 0</pose>
<name>racetrack</name>
</include>

<include>
<name>cone_A</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>5.53 6.32 0 0 0 0</pose>
</include>
<include>
<name>cone_B</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>0.8 7.57 0 0 0 0</pose>
</include>
<include>
<name>cone_C</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>-5.2 6.2 0 0 0 0</pose>
</include>
<include>
<name>cone_D</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>-5.95 1 0 0 0 0</pose>
</include>
<include>
<name>cone_E</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>-4.3 -7.1 0 0 0 0</pose>
</include>
<include>
<name>cone_F</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>-0.51 -8.33 0 0 0 0</pose>
</include>
<include>
<name>cone_G</name>
<uri>model://sim_world/models/sankaku_cone_G</uri>
<static>true</static>
<pose>4.26 -7.1 0 0 0 0</pose>
</include>
<!--
<include>
<name>beer0</name>
Expand Down

0 comments on commit 4afd268

Please sign in to comment.