Skip to content

Commit

Permalink
Remove sdf
Browse files Browse the repository at this point in the history
Signed-off-by: Vatan Aksoy Tezer <[email protected]>
  • Loading branch information
Vatan Aksoy Tezer authored and vatanaksoytezer committed May 28, 2021
1 parent 1458db3 commit c3ce98d
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 192 deletions.
11 changes: 1 addition & 10 deletions ros_ign_gazebo_demos/launch/joint_states.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,10 @@ def generate_launch_description():
)

# Spawn
rrbot_sdf = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.sdf')
spawn = Node(package='ros_ign_gazebo', executable='create',
arguments=[
'-name', 'rrbot',
'-file', rrbot_sdf,
'-topic', 'robot_description',
],
output='screen',
)
Expand All @@ -68,21 +67,13 @@ def generate_launch_description():
output='screen'
)

# Static TF between world and robot
world_static_tf = Node(package='tf2_ros',
executable='static_transform_publisher',
name='world_static_tf',
output='log',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'base_link', 'world'])

return LaunchDescription(
[
# Nodes and Launches
gazebo,
spawn,
bridge,
robot_state_publisher,
world_static_tf,
rviz,
]
)
170 changes: 0 additions & 170 deletions ros_ign_gazebo_demos/models/rrbot.sdf

This file was deleted.

61 changes: 49 additions & 12 deletions ros_ign_gazebo_demos/models/rrbot.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
</material>

<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="base_link"/>
<link name="world"/>

<joint name="fixed" type="fixed">
<parent link="base_link"/>
<parent link="world"/>
<child link="link1"/>
</joint>

Expand All @@ -49,9 +49,9 @@
<origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${mass / 12.0 * (width*width + height1*height1)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height1*height1 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
ixx="${mass / 12.0 * (width*width + height1*height1)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height1*height1 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
</inertial>
</link>

Expand All @@ -75,7 +75,7 @@
<visual>
<origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height2}"/>
<box size="${width} ${width} ${height2}"/>
</geometry>
<material name="black"/>
</visual>
Expand All @@ -84,9 +84,9 @@
<origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${mass / 12.0 * (width*width + height2*height2)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height2*height2 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
ixx="${mass / 12.0 * (width*width + height2*height2)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height2*height2 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
</inertial>
</link>

Expand Down Expand Up @@ -119,10 +119,47 @@
<origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${mass / 12.0 * (width*width + height3*height3)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height3*height3 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
ixx="${mass / 12.0 * (width*width + height3*height3)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height3*height3 + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
</inertial>
</link>

<!-- Gazebo colors and frictions -->
<!-- Link1 -->
<gazebo reference="link1">
<material>
<diffuse> 1 0.423529412 0.039215686 1</diffuse>
<ambient> 1 0.423529412 0.039215686 1</ambient>
<specular>1 0.423529412 0.039215686 1</specular>
</material>
</gazebo>

<!-- Link2 -->
<gazebo reference="link2">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>
<diffuse> 0 0 0 1</diffuse>
<ambient> 0 0 0 1</ambient>
<specular>0 0 0 1</specular>
</material>
</gazebo>

<!-- Link3 -->
<gazebo reference="link3">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>
<diffuse> 1 0.423529412 0.039215686 1</diffuse>
<ambient> 1 0.423529412 0.039215686 1</ambient>
<specular>1 0.423529412 0.039215686 1</specular>
</material>
</gazebo>

<!-- Joint states plugin -->
<gazebo>
<plugin filename="libignition-gazebo-joint-state-publisher-system.so" name="ignition::gazebo::systems::JointStatePublisher"/>
</gazebo>

</robot>

0 comments on commit c3ce98d

Please sign in to comment.