Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions ros_ign_gazebo_demos/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,4 +16,10 @@ install(
DESTINATION share/${PROJECT_NAME}/rviz
)

install(
DIRECTORY
models/
DESTINATION share/${PROJECT_NAME}/models
)

ament_package()
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.
79 changes: 79 additions & 0 deletions ros_ign_gazebo_demos/launch/joint_states.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
import os
import xacro
Comment thread
vatanaksoytezer marked this conversation as resolved.
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node

def generate_launch_description():

# Package Directories
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 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(
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
rviz = Node(
package='rviz2',
executable='rviz2',
arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'joint_states.rviz')],
)

# Spawn
spawn = Node(package='ros_ign_gazebo', executable='create',
arguments=[
'-name', 'rrbot',
'-topic', 'robot_description',
],
output='screen',
)
Comment thread
vatanaksoytezer marked this conversation as resolved.

# 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/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model',
],
remappings=[
('/world/empty/model/rrbot/joint_state', 'joint_states'),
],
output='screen'
)

return LaunchDescription(
[
# Nodes and Launches
gazebo,
spawn,
bridge,
robot_state_publisher,
rviz,
]
)
165 changes: 165 additions & 0 deletions ros_ign_gazebo_demos/models/rrbot.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
<?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="world"/>

<joint name="fixed" type="fixed">
<parent link="world"/>
<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>

<!-- 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>
Loading