Skip to content

Commit

Permalink
Add documentation for custom tf_prefix
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Apr 29, 2024
1 parent 969e880 commit f694062
Show file tree
Hide file tree
Showing 2 changed files with 104 additions and 0 deletions.
17 changes: 17 additions & 0 deletions ur_simulation_gz/doc/custom_prefix.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
Using a custom tf_prefix
========================

In case you would like to use a custom prefix to your simulated robot, you can provide one by
passing the ``tf_prefix`` to the control launchfile:

.. code-block:: bash
ros2 launch ur_simulation_gz ur_sim_control.launch.py tf_prefix:=my_ur_
However, when doing so, you will have to provide your own controller configuration file. A
corresponding file to the prefix above could look as follows:

.. literalinclude:: resources/ur_controllers.yaml

Using the ``$(var tf_prefix) notation as in the driver does not work here, since the file is loaded
differently, where (to our knowledge) no variable substitution is possible.
87 changes: 87 additions & 0 deletions ur_simulation_gz/doc/resources/ur_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
controller_manager:
ros__parameters:
update_rate: 500 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

force_torque_sensor_broadcaster:
type: ur_controllers/ForceTorqueStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

forward_velocity_controller:
type: velocity_controllers/JointGroupVelocityController

forward_position_controller:
type: position_controllers/JointGroupPositionController


speed_scaling_state_broadcaster:
ros__parameters:
state_publish_rate: 100.0
tf_prefix: "my_ur_"


force_torque_sensor_broadcaster:
ros__parameters:
sensor_name: my_ur_tcp_fts_sensor
state_interface_names:
- force.x
- force.y
- force.z
- torque.x
- torque.y
- torque.z
frame_id: tool0
topic_name: ft_data


joint_trajectory_controller:
ros__parameters:
joints:
- my_ur_shoulder_pan_joint
- my_ur_shoulder_lift_joint
- my_ur_elbow_joint
- my_ur_wrist_1_joint
- my_ur_wrist_2_joint
- my_ur_wrist_3_joint
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.2
goal_time: 0.0
my_ur_shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
my_ur_shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
my_ur_elbow_joint: {trajectory: 0.2, goal: 0.1}
my_ur_wrist_1_joint: {trajectory: 0.2, goal: 0.1}
my_ur_wrist_2_joint: {trajectory: 0.2, goal: 0.1}
my_ur_wrist_3_joint: {trajectory: 0.2, goal: 0.1}

forward_velocity_controller:
ros__parameters:
joints:
- my_ur_shoulder_pan_joint
- my_ur_shoulder_lift_joint
- my_ur_elbow_joint
- my_ur_wrist_1_joint
- my_ur_wrist_2_joint
- my_ur_wrist_3_joint
interface_name: velocity

forward_position_controller:
ros__parameters:
joints:
- my_ur_shoulder_pan_joint
- my_ur_shoulder_lift_joint
- my_ur_elbow_joint
- my_ur_wrist_1_joint
- my_ur_wrist_2_joint
- my_ur_wrist_3_joint

0 comments on commit f694062

Please sign in to comment.