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

Added prefix args to ros_control launch files and to the tool0_controller transform frame

This commit is contained in:
Thomas Timm Andersen
2016-02-19 14:58:28 +01:00
parent 0b9bf8b549
commit adc223cbd8
6 changed files with 24 additions and 9 deletions

View File

@@ -1,20 +1,24 @@
<?xml version="1.0"?>
<launch> <launch>
<!-- GDB functionality --> <!-- GDB functionality -->
<arg name="debug" default="false" /> <arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" /> <arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" /> <arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="robot_ip"/> <arg name="robot_ip"/>
<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="3.0"/>
<arg name="prefix" default="" />
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
<!-- 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>
<!-- Load hardware interface --> <!-- 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="screen" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/> <param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
@@ -22,6 +26,7 @@
<param name="max_payload" type="double" value="$(arg max_payload)"/> <param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="max_velocity" type="double" value="$(arg max_velocity)"/> <param name="max_velocity" type="double" value="$(arg max_velocity)"/>
<param name="use_ros_control" type="bool" value="True"/> <param name="use_ros_control" type="bool" value="True"/>
<arg name="prefix" value="$(arg prefix)" />
</node> </node>
<!-- Load controller settings --> <!-- Load controller settings -->

View File

@@ -25,6 +25,7 @@
<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)"/>
<arg name="prefix" value="$(arg prefix)" />
</include> </include>
</launch> </launch>

View File

@@ -1,3 +1,4 @@
<?xml version="1.0"?>
<launch> <launch>
<!-- GDB functionality --> <!-- GDB functionality -->
@@ -9,10 +10,12 @@
<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="" />
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
<!-- 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>
@@ -23,6 +26,7 @@
<param name="max_payload" type="double" value="$(arg max_payload)"/> <param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="max_velocity" type="double" value="$(arg max_velocity)"/> <param name="max_velocity" type="double" value="$(arg max_velocity)"/>
<param name="use_ros_control" type="bool" value="True"/> <param name="use_ros_control" type="bool" value="True"/>
<arg name="prefix" value="$(arg prefix)" />
</node> </node>
<!-- Load controller settings --> <!-- Load controller settings -->

View File

@@ -1,21 +1,24 @@
<?xml version="1.0"?>
<launch> <launch>
<!-- GDB functionality --> <!-- GDB functionality -->
<arg name="debug" default="false" /> <arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" /> <arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" /> <arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="robot_ip"/> <arg name="robot_ip"/>
<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="3.0"/>
<arg name="prefix" default="" />
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
<!-- 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>
<!-- Load hardware interface --> <!-- 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="screen" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/> <param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
@@ -23,6 +26,7 @@
<param name="max_payload" type="double" value="$(arg max_payload)"/> <param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="max_velocity" type="double" value="$(arg max_velocity)"/> <param name="max_velocity" type="double" value="$(arg max_velocity)"/>
<param name="use_ros_control" type="bool" value="True"/> <param name="use_ros_control" type="bool" value="True"/>
<arg name="prefix" value="$(arg prefix)" />
</node> </node>
<!-- Load controller settings --> <!-- Load controller settings -->

View File

@@ -13,8 +13,8 @@
<arg name="max_payload" /> <arg name="max_payload" />
<arg name="prefix" default="" /> <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="$(arg prefix)base_link" />
<arg name="tool_frame" default="tool0_controller"/> <arg name="tool_frame" default="$(arg prefix)tool0_controller" />
<!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits --> <!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits -->
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->

View File

@@ -157,9 +157,10 @@ public:
robot_.setServojTime(servoj_time); robot_.setServojTime(servoj_time);
//Base and tool frames //Base and tool frames
base_frame_ = "base"; base_frame_ = joint_prefix + "base_link";
tool_frame_ = "tool0_controller"; tool_frame_ = joint_prefix + "tool0_controller";
if (ros::param::get("~base_frame", base_frame_)) { if (ros::param::get("~base_frame", base_frame_)) {
base_frame_ = base_frame_;
sprintf(buf, "Base frame set to: %s", base_frame_.c_str()); sprintf(buf, "Base frame set to: %s", base_frame_.c_str());
print_debug(buf); print_debug(buf);
} }