1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 18:10:47 +02:00
Files
universal_robots_ros_driver/launch/ur3_ros_control.launch
Jarek Potiuk 6950b3c4bd Re-add urscript topic (#7)
* Re-added UR script - for custom UR Script execution

* Restarting the driver when robot closes the connection on script error.

The pipelines work in the way that if the connection is
is closed by the control PC, it will not be re-established. This
happens for example if you use the URScript topic and upload
script that does not compile. The robot will then close the
connection, the pipeline will close and any subsequent
uploads will fail and noone realises there is a problem.

While we could re-establish the connection, I think much better
solution is to shutdown the driver in such case. This is much more
resilient behaviour as it will clean up any inconsistent driver state.

We can utilise "respawn" feature of ROS launch and restart such
driver automatically (launch files are updated as part of that change).

On top of "production" stability, it allows for much nicer development
workflow - you can use URScript topic for development of new scripts
and have the driver restart every time you make mistake.
Without it, any mistake requires restarting the driver manually.
2018-01-02 20:22:55 +01:00

53 lines
2.4 KiB
XML

<?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="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" />
<!-- 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_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" />
<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_modern_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="joint_state_controller force_torque_sensor_controller vel_based_pos_traj_controller" />
<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load pos_based_pos_traj_controller" />
<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
</launch>