mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Added the servoj gain and servoj lookahead time as a parameter at launch time. Resolves #47
This commit is contained in:
@@ -19,12 +19,13 @@
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="screen" launch-prefix="$(arg launch_prefix)">
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||
<param name="min_payload" type="double" value="$(arg min_payload)"/>
|
||||
<param name="max_payload" type="double" value="$(arg max_payload)"/>
|
||||
<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)" />
|
||||
</node>
|
||||
|
||||
|
||||
@@ -19,12 +19,13 @@
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="screen" launch-prefix="$(arg launch_prefix)">
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||
<param name="min_payload" type="double" value="$(arg min_payload)"/>
|
||||
<param name="max_payload" type="double" value="$(arg max_payload)"/>
|
||||
<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)" />
|
||||
</node>
|
||||
|
||||
|
||||
@@ -19,12 +19,13 @@
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="screen" launch-prefix="$(arg launch_prefix)">
|
||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||
<param name="min_payload" type="double" value="$(arg min_payload)"/>
|
||||
<param name="max_payload" type="double" value="$(arg max_payload)"/>
|
||||
<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)" />
|
||||
</node>
|
||||
|
||||
|
||||
Reference in New Issue
Block a user