1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Updated launch files to evaluate a 'prefix' argument and pass it to the driver and urdf file. Fixes #28

This commit is contained in:
Thomas Timm Andersen
2016-02-19 14:16:49 +01:00
parent c05f16c8e9
commit 0b9bf8b549
8 changed files with 25 additions and 7 deletions

View File

@@ -13,10 +13,11 @@
<arg name="limited" default="false"/> <arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/> <arg name="max_payload" default="10.0"/>
<arg name="prefix" default="" />
<!-- robot model --> <!-- robot model -->
<include file="$(find ur_description)/launch/ur10_upload.launch"> <include file="$(find ur_description)/launch/ur10_upload.launch">
<arg name="limited" value="$(arg limited)"/> <arg name="limited" value="$(arg limited)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
<!-- ur common --> <!-- ur common -->

View File

@@ -11,12 +11,14 @@
<!-- robot_ip: IP-address of the robot's socket-messaging server --> <!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/> <arg name="robot_ip"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="20.0"/> <arg name="max_payload" default="10.0"/>
<arg name="prefix" default="" />
<include file="$(find ur_modern_driver)/launch/ur10_bringup.launch"> <include file="$(find ur_modern_driver)/launch/ur10_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="limited" value="true"/> <arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/> <arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
</launch> </launch>

View File

@@ -13,10 +13,11 @@
<arg name="limited" default="false"/> <arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="3.0"/> <arg name="max_payload" default="3.0"/>
<arg name="prefix" default="" />
<!-- robot model --> <!-- robot model -->
<include file="$(find ur_description)/launch/ur3_upload.launch"> <include file="$(find ur_description)/launch/ur3_upload.launch">
<arg name="limited" value="$(arg limited)"/> <arg name="limited" value="$(arg limited)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
<!-- ur common --> <!-- ur common -->

View File

@@ -11,12 +11,14 @@
<!-- robot_ip: IP-address of the robot's socket-messaging server --> <!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/> <arg name="robot_ip"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/> <arg name="max_payload" default="3.0"/>
<arg name="prefix" default="" />
<include file="$(find ur_modern_driver)/launch/ur3_bringup.launch"> <include file="$(find ur_modern_driver)/launch/ur3_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="limited" value="true"/> <arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/> <arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
</launch> </launch>

View File

@@ -13,14 +13,16 @@
<arg name="limited" default="false"/> <arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="5.0"/> <arg name="max_payload" default="5.0"/>
<arg name="prefix" default="" />
<!-- robot model --> <!-- robot model -->
<include file="$(find ur_description)/launch/ur5_upload.launch"> <include file="$(find ur_description)/launch/ur5_upload.launch">
<arg name="limited" value="$(arg limited)"/> <arg name="limited" value="$(arg limited)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
<!-- ur common --> <!-- ur common -->
<include file="$(find ur_modern_driver)/launch/ur_common.launch"> <include file="$(find ur_modern_driver)/launch/ur_common.launch">
<arg name="prefix" value="$(arg prefix)" />
<arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="min_payload" value="$(arg min_payload)"/> <arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/>

View File

@@ -11,12 +11,14 @@
<!-- robot_ip: IP-address of the robot's socket-messaging server --> <!-- robot_ip: IP-address of the robot's socket-messaging server -->
<arg name="robot_ip"/> <arg name="robot_ip"/>
<arg name="min_payload" default="0.0"/> <arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/> <arg name="max_payload" default="5.0"/>
<arg name="prefix" default="" />
<include file="$(find ur_modern_driver)/launch/ur5_bringup.launch"> <include file="$(find ur_modern_driver)/launch/ur5_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="limited" value="true"/> <arg name="limited" value="true"/>
<arg name="min_payload" value="$(arg min_payload)"/> <arg name="min_payload" value="$(arg min_payload)"/>
<arg name="max_payload" value="$(arg max_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
</launch> </launch>

View File

@@ -11,6 +11,7 @@
<arg name="robot_ip" /> <arg name="robot_ip" />
<arg name="min_payload" /> <arg name="min_payload" />
<arg name="max_payload" /> <arg name="max_payload" />
<arg name="prefix" default="" />
<arg name="servoj_time" default="0.008" /> <arg name="servoj_time" default="0.008" />
<arg name="base_frame" default="base"/> <arg name="base_frame" default="base"/>
<arg name="tool_frame" default="tool0_controller"/> <arg name="tool_frame" default="tool0_controller"/>
@@ -23,6 +24,7 @@
<!-- driver --> <!-- driver -->
<node name="ur_driver" pkg="ur_modern_driver" type="ur_driver" output="screen"> <node name="ur_driver" pkg="ur_modern_driver" type="ur_driver" output="screen">
<!-- copy the specified IP address to be consistant with ROS-Industrial spec. --> <!-- copy the specified IP address to be consistant with ROS-Industrial spec. -->
<param name="prefix" type="str" value="$(arg prefix)" />
<param name="robot_ip_address" type="str" value="$(arg robot_ip)" /> <param name="robot_ip_address" type="str" value="$(arg robot_ip)" />
<param name="min_payload" type="double" value="$(arg min_payload)" /> <param name="min_payload" type="double" value="$(arg min_payload)" />
<param name="max_payload" type="double" value="$(arg max_payload)" /> <param name="max_payload" type="double" value="$(arg max_payload)" />

View File

@@ -111,6 +111,12 @@ def main():
client.wait_for_server() client.wait_for_server()
print "Connected to server" print "Connected to server"
rospy.Subscriber("joint_states", JointState, joint_subscriber) rospy.Subscriber("joint_states", JointState, joint_subscriber)
parameters = rospy.get_param(None)
index = str(parameters).find('prefix')
if (index > 0):
prefix = str(parameters)[index+len("prefix': '"):(index+len("prefix': '")+str(parameters)[index+len("prefix': '"):-1].find("'"))]
for i, name in enumerate(JOINT_NAMES):
JOINT_NAMES[i] = prefix + name
print "This program makes the robot move between the following three poses:" print "This program makes the robot move between the following three poses:"
print str([Q1[i]*180./pi for i in xrange(0,6)]) print str([Q1[i]*180./pi for i in xrange(0,6)])
print str([Q2[i]*180./pi for i in xrange(0,6)]) print str([Q2[i]*180./pi for i in xrange(0,6)])