Skip to content

Commit

Permalink
Cleanup and Update readme and robot files
Browse files Browse the repository at this point in the history
  • Loading branch information
Vatan Aksoy Tezer committed May 27, 2021
1 parent 7bd17aa commit a16ffa5
Show file tree
Hide file tree
Showing 5 changed files with 54 additions and 17 deletions.
12 changes: 11 additions & 1 deletion ros_ign_gazebo_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -148,4 +148,14 @@ To try the demo launch:

ros2 launch ros_ign_gazebo_demos robot_description_publisher.launch.py

![](images/robot_state_publisher_demo.png)
![](images/robot_state_publisher_demo.png)

## Joint States Publisher

Publishes joint states of the robot.

To try the demo launch:

ros2 launch ros_ign_gazebo_demos joint_states.launch.py

![](images/joint_states.png)
Binary file added ros_ign_gazebo_demos/images/joint_states.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
24 changes: 13 additions & 11 deletions ros_ign_gazebo_demos/launch/joint_states.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,23 +13,24 @@ def generate_launch_description():
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_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}
robot_description = {'robot_description': robot_description_config}

# Robot state publisher
robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
output="both",
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='both',
parameters=[robot_description],
)

# Ignition gazebo
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')),
launch_arguments={'ign_args': '-r empty.sdf'}.items(),
)

# RViz
Expand All @@ -41,7 +42,8 @@ def generate_launch_description():
)

# 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', 'rrbot.sdf')
# rrbot_sdf_path = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot2.sdf')
print(rrbot_sdf_path)
spawn = Node(package='ros_ign_gazebo', executable='create',
arguments=[
Expand All @@ -51,18 +53,18 @@ def generate_launch_description():
output='screen',
)

# Ign Bridge
# Ign - ROS Bridge
bridge = Node(
package='ros_ign_bridge',
executable='parameter_bridge',
arguments=[
# Clock (IGN -> ROS2)
'/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock',
# Joint states (IGN -> ROS2)
'/world/default/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model',
'/world/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model',
],
remappings=[
("/world/default/model/rrbot/joint_state", "joint_states"),
('/world/empty/model/rrbot/joint_state', 'joint_states'),
],
output='screen'
)
Expand All @@ -72,7 +74,7 @@ def generate_launch_description():
executable='static_transform_publisher',
name='world_static_tf',
output='log',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'link1', 'world'])
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'base_link', 'world'])

return LaunchDescription(
[
Expand Down
28 changes: 23 additions & 5 deletions ros_ign_gazebo_demos/models/rrbot.sdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,25 @@
<sdf version='1.7'>
<model name='rrbot'>
<link name='base_link'>
<inertial>
<pose>0 0 1 0 -0 0</pose>
<mass>10</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
</link>
<joint name='fixed_joint' type='fixed'>
<parent>base_link</parent>
<child>link1</child>
</joint>
<link name='link1'>
<pose>0 0 0 0 -0 0</pose>
<pose relative_to='base_link'>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 1 0 -0 0</pose>
<mass>1</mass>
Expand Down Expand Up @@ -47,8 +65,8 @@
<upper>1e+16</upper>
</limit>
<dynamics>
<damping>0.7</damping>
<friction>0.0</friction>
<damping>21.75</damping>
<friction>3.48</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand Down Expand Up @@ -101,8 +119,8 @@
<upper>1e+16</upper>
</limit>
<dynamics>
<damping>0.7</damping>
<friction>0.0</friction>
<damping>21.75</damping>
<friction>3.48</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
Expand Down
7 changes: 7 additions & 0 deletions ros_ign_gazebo_demos/models/rrbot.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,13 @@
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="base_link"/>
<joint name="fixed_joint" type="fixed">
<parent link="base_link"/>
<child link="link1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<!-- Base Link -->
<link name="link1">
<collision>
Expand Down

0 comments on commit a16ffa5

Please sign in to comment.