Skip to content

Commit

Permalink
Joint state publisher and tf bridging demo (#244)
Browse files Browse the repository at this point in the history
* Added joint state publisher and tf bridge demo

Signed-off-by: Aditya <aditya050995@gmail.com>

Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
adityapande-1995 and chapulina committed Apr 25, 2022
1 parent ecd7b7e commit 8efbf57
Show file tree
Hide file tree
Showing 5 changed files with 490 additions and 0 deletions.
11 changes: 11 additions & 0 deletions ros_ign_gazebo_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -187,3 +187,14 @@ To try the demo launch:
ros2 launch ros_ign_gazebo_demos joint_states.launch.py

![](images/joint_states.png)

## Bridging joint state and pose publishers

The launch file demonstrates bridging ignition poses to TFMessage to visualize the pose
and transforms of a robot in rviz.

To try the demo launch:

ros2 launch ros_ign_gazebo_demos tf_bridge.launch.py

![](images/tf_bridge.gif)
Binary file added ros_ign_gazebo_demos/images/tf_bridge.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
50 changes: 50 additions & 0 deletions ros_ign_gazebo_demos/launch/tf_bridge.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
# Copyright 2022 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import ExecuteProcess
from launch_ros.actions import Node

def generate_launch_description():
pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos')
return LaunchDescription([
# Launch gazebo
ExecuteProcess(
cmd=['ign','gazebo', '-r', os.path.join(pkg_ros_ign_gazebo_demos,
'models', 'double_pendulum_model.sdf')]
),
# Launch a bridge to forward tf and joint states to ros2
Node(
package='ros_ign_bridge',
executable='parameter_bridge',
arguments=[
'/world/default/model/double_pendulum_with_base0/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model',
'/model/double_pendulum_with_base0/pose@tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V'
],
remappings=[
('/model/double_pendulum_with_base0/pose','/tf'),
('/world/default/model/double_pendulum_with_base0/joint_state','/joint_states')
]
),
# Launch rviz
Node(
package='rviz2',
executable='rviz2',
arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'tf_bridge.rviz')]
)
])
266 changes: 266 additions & 0 deletions ros_ign_gazebo_demos/models/double_pendulum_model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,266 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
</physics>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="double_pendulum_with_base0">
<pose>0 0 0 0 0 0</pose>
<frame name="base_frame" />
<link name="base">
<inertial>
<mass>100</mass>
</inertial>
<visual name="vis_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 2.2</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
<collision name="col_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 2.2</size>
</box>
</geometry>
</collision>
</link>
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- lower link, length 1, IC ~-120 degrees more -->
<link name="lower_link">
<pose>0.25 1.0 2.1 -2 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<collision name="col_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- pin joint for upper link, at origin of upper link -->
<joint name="upper_joint" type="revolute">
<parent>base</parent>
<child>upper_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
<!-- pin joint for lower link, at origin of child link -->
<joint name="lower_joint" type="revolute">
<parent>upper_link</parent>
<child>lower_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>

<plugin
filename="ignition-gazebo-joint-state-publisher-system"
name="ignition::gazebo::systems::JointStatePublisher">
</plugin>

<plugin
filename="ignition-gazebo-pose-publisher-system"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>true</publish_link_pose>

<use_pose_vector_msg>true</use_pose_vector_msg>
</plugin>

</model>

</world>
</sdf>
Loading

0 comments on commit 8efbf57

Please sign in to comment.