mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 18:10:47 +02:00
Expose tool pose/twist from RT when ros_control is active.
Replicates #20 for the case where ros_control is active.
This commit is contained in:
@@ -12,6 +12,8 @@
|
||||
<arg name="max_payload" default="3.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur5_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
@@ -26,7 +28,9 @@
|
||||
<param name="max_velocity" type="double" value="$(arg max_velocity)"/>
|
||||
<param name="use_ros_control" type="bool" value="True"/>
|
||||
<param name="servoj_gain" type="double" value="750" />
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<param name="prefix" value="$(arg prefix)" />
|
||||
<param name="base_frame" type="str" value="$(arg base_frame)"/>
|
||||
<param name="tool_frame" type="str" value="$(arg tool_frame)"/>
|
||||
</node>
|
||||
|
||||
<!-- Load controller settings -->
|
||||
|
||||
Reference in New Issue
Block a user