Skip to content

Commit

Permalink
making spawn changes and adding double handed cargo (#97)
Browse files Browse the repository at this point in the history
  • Loading branch information
marinagmoreira authored Jun 26, 2023
1 parent dcf6689 commit f6393b6
Show file tree
Hide file tree
Showing 9 changed files with 308 additions and 236 deletions.
25 changes: 5 additions & 20 deletions astrobee/simulation/isaac_gazebo/launch/spawn_object.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,26 +21,11 @@
<arg name="spawn" default=""/> <!-- Object to spawn -->
<arg name="name" default="object"/> <!-- Name of object -->
<arg name="pose" default="0 0 0 0 0 0 1"/>

<!-- <arg if="$(eval arg('position')=='vent')"
name="pose"
default="10.1069 -3.16958 4.90421 0.707 0.0 0.0 0.707" /> --> <!-- obstructing vent 1 default="9.942 -4.21 3.9105 0 0.335 0 0.942" -->
<!-- <arg if="$(eval arg('position')=='other1')"
name="pose"
default="2 0 5.1 0 0 0 1" /> --> <!-- other 1 -->
<!-- <arg if="$(eval arg('position')=='other2')"
name="pose"
default="0 0 5.1 0 0 0 1" /> --> <!-- other 2 -->


<!-- Spawn Sock into Gazebo -->
<group if="$(eval arg('spawn')=='sock')" ns="object">
<param name="sock_description" command='$(find xacro)/xacro --inorder $(find isaac_description)/urdf/socks.urdf.xacro' />
<node name="sock" pkg="astrobee_gazebo" type="spawn_model" args="-param sock_description -urdf -model $(arg name) -pose $(arg pose) "/>
</group>
<group if="$(eval arg('spawn')=='cargo')" ns="object">
<param name="cargo_description" command='$(find xacro)/xacro --inorder $(find isaac_description)/urdf/cargo_bag.urdf.xacro' />
<node name="cargo" pkg="astrobee_gazebo" type="spawn_model" args="-param cargo_description -urdf -model $(arg name) -pose $(arg pose) "/>

<!-- Spawn object into Gazebo -->
<group ns="$(arg name)">
<param name="$(arg spawn)_description" command='$(find xacro)/xacro --inorder $(find isaac_description)/urdf/$(arg spawn).urdf.xacro' />
<node name="$(arg name)" pkg="astrobee_gazebo" type="spawn_model" args="-param $(arg spawn)_description -urdf -model $(arg name) -pose $(arg pose) "/>
</group>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<arg name="world" default="worlds/empty.world"/>
<arg name="speed" default="1"/>
<arg name="debug" default="false"/>
<arg name="physics" default="ode"/>

<!-- Use simulation time -->
<param name="/use_sim_time" value="true" />
Expand All @@ -31,12 +32,12 @@
<group if="$(arg debug)">
<node name="gazebo" pkg="gazebo_ros" type="debug"
respawn="false" output="screen"
args="$(arg world)" />
args="-e $(arg physics) $(arg world)" />
</group>
<group unless="$(arg debug)">
<node name="gazebo" pkg="astrobee_gazebo" type="start_server"
respawn="false" output="screen"
args="$(arg world)" />
args="-e $(arg physics) $(arg world)" />
</group>

<!-- start gazebo client -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@
<robot name="cargo" xmlns:xacro="http://www.ros.org/wiki/xacro">

<link name="body">
<!-- <collision>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://isaac_description/meshes/half_ctb_02_4.dae" scale="1 1 1"/>
</geometry>
</collision> -->
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
Expand Down
62 changes: 62 additions & 0 deletions description/urdf/cargo_double.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
<?xml version="1.0"?>
<robot name="cargo" xmlns:xacro="http://www.ros.org/wiki/xacro">

<link name="body">
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://isaac_description/meshes/half_ctb_02_4.dae" scale="1 1 1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://isaac_description/meshes/half_ctb_02_4.dae" scale="1 1 1"/>
</geometry>
</visual>

<collision>
<origin xyz="0.1 0.21 0" rpy="0 0 1.57" />
<geometry>
<mesh filename="package://astrobee_handrail_8_5/meshes/handrail_8_5.dae"/>
</geometry>
</collision>
<visual>
<origin xyz="0.1 0.21 0" rpy="0 0 1.57" />
<geometry>
<mesh filename="package://astrobee_handrail_8_5/meshes/handrail_8_5.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.1 -0.21 0" rpy="0 0 -1.57" />
<geometry>
<mesh filename="package://astrobee_handrail_8_5/meshes/handrail_8_5.dae"/>
</geometry>
</collision>
<visual>
<origin xyz="0.1 -0.21 0" rpy="0 0 -1.57" />
<geometry>
<mesh filename="package://astrobee_handrail_8_5/meshes/handrail_8_5.dae"/>
</geometry>
</visual>

<inertial>
<mass value="0.5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
</inertial>
</link>

<!-- tf publisher -->
<gazebo>
<plugin name="truth_ros" filename="libgazebo_model_plugin_truth.so">
<rate>62.5</rate>
<parent>world</parent>
<child>body</child>
<tf>true</tf>
<pose>false</pose>
<twist>false</twist>
<static>false</static>
</plugin>
</gazebo>
</robot>
File renamed without changes.
2 changes: 2 additions & 0 deletions isaac/launch/controller/sim_start.launch
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<arg name="vmware" default="true" />
<arg name="speed" default="1" />
<arg name="debug" default="false" />
<arg name="physics" default="ode"/>
<!-- Fix for running in vmware with DRI -->
<env if="$(arg vmware)" name="SVGA_VGPU10" value="0" />
<!-- Launch the requested world -->
Expand All @@ -30,5 +31,6 @@
<arg name="gui" value="$(arg gzclient)"/>
<arg name="speed" value="$(arg speed)" />
<arg name="debug" value="$(arg debug)" />
<arg name="physics" value="$(arg physics)" />
</include>
</launch>
4 changes: 4 additions & 0 deletions isaac/launch/sim.launch
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@
<arg name="nodes" default=""/> <!-- Launch specific nodes -->
<arg name="extra" default=""/> <!-- Inject additional node -->
<arg name="debug" default=""/> <!-- Debug node group -->
<!-- Physics engine options: ode (gazebo default), bullet, simbody, dart -->
<arg name="physics" default="ode"/>
<arg name="sim" default="local" /> <!-- SIM IP address -->
<arg name="llp" default="local" /> <!-- LLP IP address -->
<arg name="mlp" default="local" /> <!-- MLP IP address -->
Expand Down Expand Up @@ -166,6 +168,7 @@
<arg name="vmware" value="$(arg vmware)" />
<arg name="speed" value="$(arg speed)" />
<arg name="debug" value="$(arg sdebug)" />
<arg name="physics" value="$(arg physics)" />
</include>
</group>
<group if="$(arg r2)">
Expand All @@ -175,6 +178,7 @@
<arg name="vmware" value="$(arg vmware)" />
<arg name="speed" value="$(arg speed)" />
<arg name="debug" value="$(arg sdebug)" />
<arg name="physics" value="$(arg physics)" />
</include>
</group>
</group>
Expand Down
Loading

0 comments on commit f6393b6

Please sign in to comment.