mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
moved calibration to own repository
This commit is contained in:
54
ur_rtde_driver/launch/ur10_bringup.launch
Normal file
54
ur_rtde_driver/launch/ur10_bringup.launch
Normal file
@@ -0,0 +1,54 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur10 launch. Loads ur10 robot description (see ur_common.launch
|
||||
for more info)
|
||||
|
||||
Usage:
|
||||
ur10_bringup.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="10.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur10_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
<!-- ur common -->
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
55
ur_rtde_driver/launch/ur10_bringup_compatible.launch
Normal file
55
ur_rtde_driver/launch/ur10_bringup_compatible.launch
Normal file
@@ -0,0 +1,55 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur10 launch. Loads ur10 robot description (see ur_common.launch
|
||||
for more info)
|
||||
|
||||
Usage:
|
||||
ur10_bringup.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="10.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.08"/>
|
||||
<arg name="servoj_time" default="0.08" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur10_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
<!-- ur common -->
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
48
ur_rtde_driver/launch/ur10_bringup_joint_limited.launch
Normal file
48
ur_rtde_driver/launch/ur10_bringup_joint_limited.launch
Normal file
@@ -0,0 +1,48 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur10 launch. Wraps ur10_bringup.launch. Uses the 'limited'
|
||||
joint range [-PI, PI] on all joints.
|
||||
|
||||
Usage:
|
||||
ur10_bringup_joint_limited.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="10.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur10_bringup.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="limited" value="true"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
</launch>
|
||||
56
ur_rtde_driver/launch/ur10_ros_control.launch
Normal file
56
ur_rtde_driver/launch/ur10_ros_control.launch
Normal file
@@ -0,0 +1,56 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- GDB functionality -->
|
||||
<arg name="debug" default="false" />
|
||||
<arg unless="$(arg debug)" name="launch_prefix" value="" />
|
||||
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
|
||||
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<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" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller"/>
|
||||
<arg name="stopped_controllers" default=""/>
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur10_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_rtde_driver_node" output="screen" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip" type="str" value="$(arg robot_ip)"/>
|
||||
<!--<param name="reverse_port" type="int" value="$(arg reverse_port)" />-->
|
||||
<!--<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" />-->
|
||||
<!--<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)"/>-->
|
||||
<!--<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>-->
|
||||
</node>
|
||||
|
||||
<!-- Load controller settings -->
|
||||
<rosparam file="$(find ur_rtde_driver)/config/ur10_controllers.yaml" command="load"/>
|
||||
|
||||
<!-- spawn controller manager -->
|
||||
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
||||
output="screen" args="$(arg controllers)" />
|
||||
|
||||
<!-- load other controller -->
|
||||
<!--<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"-->
|
||||
<!--output="screen" args="load $(arg stopped_controllers)" />-->
|
||||
|
||||
<!-- Convert joint states to /tf tranforms -->
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
|
||||
</launch>
|
||||
54
ur_rtde_driver/launch/ur3_bringup.launch
Normal file
54
ur_rtde_driver/launch/ur3_bringup.launch
Normal file
@@ -0,0 +1,54 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur3 launch. Loads ur3 robot description (see ur_common.launch
|
||||
for more info)
|
||||
|
||||
Usage:
|
||||
ur3_bringup.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="3.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur3_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
<!-- ur common -->
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
48
ur_rtde_driver/launch/ur3_bringup_joint_limited.launch
Normal file
48
ur_rtde_driver/launch/ur3_bringup_joint_limited.launch
Normal file
@@ -0,0 +1,48 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur3 launch. Wraps ur3_bringup.launch. Uses the 'limited'
|
||||
joint range [-PI, PI] on all joints.
|
||||
|
||||
Usage:
|
||||
ur3_bringup_joint_limited.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="3.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur3_bringup.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="limited" value="true"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
</launch>
|
||||
56
ur_rtde_driver/launch/ur3_ros_control.launch
Normal file
56
ur_rtde_driver/launch/ur3_ros_control.launch
Normal file
@@ -0,0 +1,56 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- GDB functionality -->
|
||||
<arg name="debug" default="false" />
|
||||
<arg unless="$(arg debug)" name="launch_prefix" value="" />
|
||||
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
|
||||
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<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" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<arg name="controllers" default="joint_state_controller force_torque_sensor_controller vel_based_pos_traj_controller"/>
|
||||
<arg name="stopped_controllers" default="pos_based_pos_traj_controller joint_group_vel_controller"/>
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur3_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
|
||||
<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" />
|
||||
<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)"/>
|
||||
<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>
|
||||
</node>
|
||||
|
||||
<!-- Load controller settings -->
|
||||
<rosparam file="$(find ur_rtde_driver)/config/ur3_controllers.yaml" command="load"/>
|
||||
|
||||
<!-- spawn controller manager -->
|
||||
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
||||
output="screen" args="$(arg controllers)" />
|
||||
|
||||
<!-- load other controller -->
|
||||
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
|
||||
output="screen" args="load $(arg stopped_controllers)" />
|
||||
|
||||
<!-- Convert joint states to /tf tranforms -->
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
|
||||
</launch>
|
||||
54
ur_rtde_driver/launch/ur5_bringup.launch
Normal file
54
ur_rtde_driver/launch/ur5_bringup.launch
Normal file
@@ -0,0 +1,54 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur5 launch. Loads ur5 robot description (see ur_common.launch
|
||||
for more info)
|
||||
|
||||
Usage:
|
||||
ur5_bringup.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="5.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur5_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
<!-- ur common -->
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
55
ur_rtde_driver/launch/ur5_bringup_compatible.launch
Normal file
55
ur_rtde_driver/launch/ur5_bringup_compatible.launch
Normal file
@@ -0,0 +1,55 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur5 launch. Loads ur5 robot description (see ur_common.launch
|
||||
for more info)
|
||||
|
||||
Usage:
|
||||
ur5_bringup.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="5.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.08"/>
|
||||
<arg name="servoj_time" default="0.08" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur5_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
<!-- ur common -->
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
48
ur_rtde_driver/launch/ur5_bringup_joint_limited.launch
Normal file
48
ur_rtde_driver/launch/ur5_bringup_joint_limited.launch
Normal file
@@ -0,0 +1,48 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot ur5 launch. Wraps ur5_bringup.launch. Uses the 'limited'
|
||||
joint range [-PI, PI] on all joints.
|
||||
|
||||
Usage:
|
||||
ur5_bringup_joint_limited.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<arg name="max_payload" default="5.0"/>
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur5_bringup.launch">
|
||||
<arg name="robot_ip" value="$(arg robot_ip)"/>
|
||||
<arg name="reverse_port" value="$(arg reverse_port)"/>
|
||||
<arg name="limited" value="true"/>
|
||||
<arg name="min_payload" value="$(arg min_payload)"/>
|
||||
<arg name="max_payload" value="$(arg max_payload)"/>
|
||||
<arg name="prefix" value="$(arg prefix)" />
|
||||
<arg name="use_lowbandwidth_trajectory_follower" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<arg name="time_interval" value="$(arg time_interval)"/>
|
||||
<arg name="servoj_time" value="$(arg servoj_time)" />
|
||||
<arg name="servoj_time_waiting" default="$(arg servoj_time_waiting)" />
|
||||
<arg name="max_waiting_time" value="$(arg max_waiting_time)" />
|
||||
<arg name="servoj_gain" value="$(arg servoj_gain)" />
|
||||
<arg name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)" />
|
||||
<arg name="max_joint_difference" value="$(arg max_joint_difference)" />
|
||||
<arg name="base_frame" value="$(arg base_frame)" />
|
||||
<arg name="tool_frame" value="$(arg tool_frame)" />
|
||||
<arg name="shutdown_on_disconnect" value="$(arg shutdown_on_disconnect)"/>
|
||||
</include>
|
||||
</launch>
|
||||
56
ur_rtde_driver/launch/ur5_ros_control.launch
Normal file
56
ur_rtde_driver/launch/ur5_ros_control.launch
Normal file
@@ -0,0 +1,56 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- GDB functionality -->
|
||||
<arg name="debug" default="false" />
|
||||
<arg unless="$(arg debug)" name="launch_prefix" value="" />
|
||||
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
|
||||
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="limited" default="false"/>
|
||||
<arg name="min_payload" default="0.0"/>
|
||||
<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" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
<arg name="controllers" default="joint_state_controller force_torque_sensor_controller vel_based_pos_traj_controller"/>
|
||||
<arg name="stopped_controllers" default="pos_based_pos_traj_controller joint_group_vel_controller"/>
|
||||
<!-- robot model -->
|
||||
<include file="$(find ur_description)/launch/ur5_upload.launch">
|
||||
<arg name="limited" value="$(arg limited)"/>
|
||||
</include>
|
||||
|
||||
|
||||
<!-- Load hardware interface -->
|
||||
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
|
||||
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||
<param name="reverse_port" type="int" value="$(arg reverse_port)" />
|
||||
<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" />
|
||||
<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)"/>
|
||||
<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>
|
||||
</node>
|
||||
|
||||
<!-- Load controller settings -->
|
||||
<rosparam file="$(find ur_rtde_driver)/config/ur5_controllers.yaml" command="load"/>
|
||||
|
||||
<!-- spawn controller manager -->
|
||||
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
||||
output="screen" args="$(arg controllers)" />
|
||||
|
||||
<!-- load other controller -->
|
||||
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
|
||||
output="screen" args="load $(arg stopped_controllers)" />
|
||||
|
||||
<!-- Convert joint states to /tf tranforms -->
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||
|
||||
</launch>
|
||||
60
ur_rtde_driver/launch/ur_common.launch
Normal file
60
ur_rtde_driver/launch/ur_common.launch
Normal file
@@ -0,0 +1,60 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Universal robot common bringup. Starts ur driver node and robot state
|
||||
publisher (translates joint positions to propper tfs).
|
||||
|
||||
Usage:
|
||||
ur_common.launch robot_ip:=<value>
|
||||
-->
|
||||
<launch>
|
||||
<!-- robot_ip: IP-address of the robot's socket-messaging server -->
|
||||
<arg name="robot_ip" />
|
||||
<arg name="reverse_port" default="50001"/>
|
||||
<arg name="min_payload" />
|
||||
<arg name="max_payload" />
|
||||
<arg name="prefix" default="" />
|
||||
<arg name="use_ros_control" default="false"/>
|
||||
<arg name="use_lowbandwidth_trajectory_follower" default="false"/>
|
||||
<arg name="time_interval" default="0.008"/>
|
||||
<arg name="servoj_time" default="0.008" />
|
||||
<arg name="servoj_time_waiting" default="0.001" />
|
||||
<arg name="max_waiting_time" default="2.0" />
|
||||
<arg name="servoj_gain" default="100." />
|
||||
<arg name="servoj_lookahead_time" default="1." />
|
||||
<arg name="max_joint_difference" default="0.01" />
|
||||
<arg name="base_frame" default="$(arg prefix)base" />
|
||||
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
|
||||
<arg name="shutdown_on_disconnect" default="true" />
|
||||
|
||||
<!-- require_activation defines when the service /ur_driver/robot_enable needs to be called. -->
|
||||
<arg name="require_activation" default="Never" /> <!-- Never, Always, OnStartup -->
|
||||
|
||||
<!-- 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] -->
|
||||
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
||||
|
||||
<!-- driver -->
|
||||
<node name="ur_driver" pkg="ur_rtde_driver" type="ur_driver" output="screen">
|
||||
<!-- 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="reverse_port" type="int" value="$(arg reverse_port)" />
|
||||
<param name="use_ros_control" type="bool" value="$(arg use_ros_control)"/>
|
||||
<param name="use_lowbandwidth_trajectory_follower" type="bool" value="$(arg use_lowbandwidth_trajectory_follower)"/>
|
||||
<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="time_interval" type="double" value="$(arg time_interval)" />
|
||||
<param name="servoj_time" type="double" value="$(arg servoj_time)" />
|
||||
<param name="servoj_time_waiting" type="double" value="$(arg servoj_time_waiting)" />
|
||||
<param name="max_waiting_time" type="double" value="$(arg max_waiting_time)" />
|
||||
<param name="servoj_gain" type="double" value="$(arg servoj_gain)" />
|
||||
<param name="servoj_lookahead_time" type="double" value="$(arg servoj_lookahead_time)" />
|
||||
<param name="max_joint_difference" type="double" value="$(arg max_joint_difference)" />
|
||||
<param name="base_frame" type="str" value="$(arg base_frame)"/>
|
||||
<param name="tool_frame" type="str" value="$(arg tool_frame)"/>
|
||||
<param name="require_activation" type="str" value="$(arg require_activation)" />
|
||||
<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>
|
||||
</node>
|
||||
</launch>
|
||||
Reference in New Issue
Block a user