Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Added]: Joint State Publisher Plugin in Gazebo #4

Merged
merged 2 commits into from
Aug 21, 2024
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
62 changes: 1 addition & 61 deletions workspace/src/ur_description/launch/robot_rviz.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,52 +3,10 @@

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import LaunchConfigurationEquals
from launch.substitutions import Command, PathJoinSubstitution
from launch.substitutions.launch_configuration import LaunchConfiguration
from launch_ros.parameter_descriptions import ParameterValue
from launch_ros.actions import Node

ARGUMENTS = [
DeclareLaunchArgument(
"use_sim_time",
default_value="true",
choices=["true", "false"],
description="Use sim time",
),
DeclareLaunchArgument(
"log_level",
default_value="error",
choices=["info", "warn", "error"],
description="log level",
),
DeclareLaunchArgument(
"model",
default_value="ur5",
description="Model to spawn",
),
DeclareLaunchArgument(
"model_xacro",
default_value=[LaunchConfiguration("model"), ".xacro"],
description="Xacro file for the Model",
),
]


def generate_launch_description():
# Get the path of the ur_description package
pkg_ur_description = get_package_share_directory("ur_description")

# Ensure pkg_ur_description is converted to string before using it
pkg_ur_description = str(pkg_ur_description)

# Construct the path to the Xacro file
xacro_file = PathJoinSubstitution(
[pkg_ur_description, "urdf", LaunchConfiguration("model_xacro")]
)

robot_desc = ParameterValue(Command(["xacro ", xacro_file]), value_type=str)

rviz_config_path = os.path.join(
get_package_share_directory("ur_description"), "rviz", "default.rviz"
Expand All @@ -57,22 +15,4 @@ def generate_launch_description():
package="rviz2", executable="rviz2", arguments=["-d", rviz_config_path]
)

joint_state_publisher_gui = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
)

ur_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="ur_state_publisher",
output="screen",
parameters=[
{"use_sim_time": LaunchConfiguration("use_sim_time")},
{"robot_description": robot_desc},
],
arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")],
remappings=[("/tf", "tf"), ("/tf_static", "tf_static")],
)

return LaunchDescription(ARGUMENTS + [ur_state_publisher,joint_state_publisher_gui,rviz_node])
return LaunchDescription([rviz_node])
4 changes: 4 additions & 0 deletions workspace/src/ur_description/urdf/inc/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -333,4 +333,8 @@
<child link="${prefix}tool0"/>
</joint>
</xacro:macro>
<gazebo>
<plugin filename="ignition-gazebo-joint-state-publisher-system"
name="ignition::gazebo::systems::JointStatePublisher" />
</gazebo>
</robot>
4 changes: 2 additions & 2 deletions workspace/src/ur_description/urdf/ur5.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,6 @@

Refer to 'inc/ur_macro.xacro' for more information.
-->
<xacro:include filename="$(find ur_description)/urdf/inc/ur5_macro.xacro"/>
<xacro:include filename="$(find ur_description)/urdf/inc/ur5_macro.xacro" />
<xacro:ur5_robot prefix="" />
</robot>
</robot>
62 changes: 60 additions & 2 deletions workspace/src/ur_simulator/ur_gz_bringup/launch/sil.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,12 @@
choices=["true", "false"],
description="Run description",
),
DeclareLaunchArgument(
"rviz",
default_value="false",
choices=["true", "false"],
description="Run rviz",
),
DeclareLaunchArgument(
"spawn_model",
default_value="true",
Expand Down Expand Up @@ -106,15 +112,67 @@ def generate_launch_description():
launch_arguments={"gz_args": LaunchConfiguration("world_sdf")}.items(),
)

rviz_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[
get_package_share_directory("ur_description"),
"launch",
"robot_rviz.launch.py",
]
)
),
condition=IfCondition(LaunchConfiguration("rviz")),
)

spawn_robot = Node(
package="ros_gz_sim",
executable="create",
parameters=[{"use_sim_time": LaunchConfiguration("use_sim_time")}],
arguments=["-name", "ur5", "-file", urdf_file, "-z", "1.0"],
arguments=[
"-name",
LaunchConfiguration("model"),
"-topic",
"robot_description",
"-z",
"1.0",
],
output="screen",
condition=IfCondition(LaunchConfiguration("spawn_model")),
)

bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
# Clock (IGN -> ROS2)
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
# Joint states (IGN -> ROS2)
[
"/world/",
LaunchConfiguration("world"),
"/model/",
LaunchConfiguration("model"),
"/joint_state",
"@sensor_msgs/msg/JointState[gz.msgs.Model",
],
],
remappings=[
(
[
"/world/",
LaunchConfiguration("world"),
"/model/",
LaunchConfiguration("model"),
"/joint_state",
],
"joint_states",
),
],
output="screen",
)

return LaunchDescription(
ARGUMENTS + [process_xacro, gz_sim, robot_description, spawn_robot]
ARGUMENTS
+ [process_xacro, gz_sim, robot_description, spawn_robot, rviz_node, bridge]
)
4 changes: 2 additions & 2 deletions workspace/src/ur_world/worlds/basic_world.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>
<sdf version="1.10">
<world name="car_world">
<sdf version="1.8">
<world name="basic_world">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
Expand Down