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

Use sjtc and generate /clock topic #58

Draft
wants to merge 4 commits into
base: ros2
Choose a base branch
from
Draft
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
1 change: 1 addition & 0 deletions ur_simulation_gz/config/ur_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ scaled_joint_trajectory_controller:
state_interfaces:
- position
- velocity
speed_scaling_interface_name: ""
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
Expand Down
13 changes: 12 additions & 1 deletion ur_simulation_gz/launch/ur_sim_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,16 @@ def launch_setup(context, *args, **kwargs):
}.items(),
)

# Make the /clock topic available in ROS
gz_sim_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
],
output="screen",
)

nodes_to_start = [
robot_state_publisher_node,
joint_state_broadcaster_spawner,
Expand All @@ -177,6 +187,7 @@ def launch_setup(context, *args, **kwargs):
initial_joint_controller_spawner_started,
gz_spawn_entity,
gz_launch_description,
gz_sim_bridge,
]

return nodes_to_start
Expand Down Expand Up @@ -243,7 +254,7 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"initial_joint_controller",
default_value="joint_trajectory_controller",
default_value="scaled_joint_trajectory_controller",
description="Robot controller to start.",
)
)
Expand Down
4 changes: 3 additions & 1 deletion ur_simulation_gz/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,14 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>ros_gz_sim</exec_depend>
<exec_depend>gz_ros2_control</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>launch</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>ros_gz_bridge</exec_depend>
<exec_depend>ros_gz_sim</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>ur_controllers</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>ur_moveit_config</exec_depend>
<exec_depend>urdf</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion ur_simulation_gz/test/test_gz.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ def tearDownClass(cls):
def init_robot(self):
self._follow_joint_trajectory = ActionInterface(
self.node,
"/joint_trajectory_controller/follow_joint_trajectory",
"/scaled_joint_trajectory_controller/follow_joint_trajectory",
FollowJointTrajectory,
)
# TODO: Replace this timeout with a proper check whether the robot is initialized
Expand Down
Loading