Skip to content

Commit

Permalink
Review fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Vatan Aksoy Tezer committed May 27, 2021
1 parent a16ffa5 commit 9e79287
Show file tree
Hide file tree
Showing 4 changed files with 142 additions and 110 deletions.
17 changes: 8 additions & 9 deletions ros_ign_gazebo_demos/launch/joint_states.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@ def generate_launch_description():
pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo')
pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos')

# Parse robot description from urdf
robot_description_file = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.urdf')
robot_description_config = open(robot_description_file).read()
robot_description = {'robot_description': robot_description_config}
# Parse robot description from xacro
robot_description_file = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.xacro')
robot_description_config = xacro.process_file(
robot_description_file
)
robot_description = {"robot_description": robot_description_config.toxml()}

# Robot state publisher
robot_state_publisher = Node(
Expand All @@ -38,17 +40,14 @@ def generate_launch_description():
package='rviz2',
executable='rviz2',
arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'joint_states.rviz')],
parameters=[]
)

# Spawn
rrbot_sdf_path = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.sdf')
# rrbot_sdf_path = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot2.sdf')
print(rrbot_sdf_path)
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_path,
'-file', rrbot_sdf,
],
output='screen',
)
Expand Down
12 changes: 6 additions & 6 deletions ros_ign_gazebo_demos/models/rrbot.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
<model name='rrbot'>
<link name='base_link'>
<inertial>
<pose>0 0 1 0 -0 0</pose>
<mass>10</mass>
<pose>0 0 0 0 -0 0</pose>
<mass>100</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
Expand Down Expand Up @@ -65,8 +65,8 @@
<upper>1e+16</upper>
</limit>
<dynamics>
<damping>21.75</damping>
<friction>3.48</friction>
<damping>0.7</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand Down Expand Up @@ -119,8 +119,8 @@
<upper>1e+16</upper>
</limit>
<dynamics>
<damping>21.75</damping>
<friction>3.48</friction>
<damping>0.7</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand Down
95 changes: 0 additions & 95 deletions ros_ign_gazebo_demos/models/rrbot.urdf

This file was deleted.

128 changes: 128 additions & 0 deletions ros_ign_gazebo_demos/models/rrbot.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
<?xml version="1.0"?>
<!-- Revolute-Revolute Manipulator -->
<robot name="rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="mass" value="1" /> <!-- arbitrary value for mass -->
<xacro:property name="width" value="0.1" /> <!-- Square dimensions (widthxwidth) of beams -->
<xacro:property name="height1" value="2" /> <!-- Link 1 -->
<xacro:property name="height2" value="1" /> <!-- Link 2 -->
<xacro:property name="height3" value="1" /> <!-- Link 3 -->
<xacro:property name="axel_offset" value="0.05" /> <!-- Space btw top of beam and the each joint -->

<!-- Define colors -->
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>

<material name="orange">
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
</material>

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

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

<!-- Base Link -->
<link name="link1">
<collision>
<origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height1}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height1}"/>
</geometry>
<material name="orange"/>
</visual>

<inertial>
<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)}"/>
</inertial>
</link>

<joint name="joint1" type="continuous">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0 ${width} ${height1 - axel_offset}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
</joint>

<!-- Middle Link -->
<link name="link2">
<collision>
<origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height2}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height2}"/>
</geometry>
<material name="black"/>
</visual>

<inertial>
<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)}"/>
</inertial>
</link>

<joint name="joint2" type="continuous">
<parent link="link2"/>
<child link="link3"/>
<origin xyz="0 ${width} ${height2 - axel_offset*2}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
</joint>

<!-- Top Link -->
<link name="link3">
<collision>
<origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height3}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/>
<geometry>
<box size="${width} ${width} ${height3}"/>
</geometry>
<material name="orange"/>
</visual>

<inertial>
<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)}"/>
</inertial>
</link>

</robot>

0 comments on commit 9e79287

Please sign in to comment.