mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
51 lines
2.3 KiB
XML
51 lines
2.3 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" />
|
|
<!-- 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)"/>
|
|
</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 velocity_based_position_trajectory_controller" />
|
|
|
|
<!-- load other controller -->
|
|
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
|
|
output="screen" args="load position_based_position_trajectory_controller" />
|
|
|
|
<!-- Convert joint states to /tf tranforms -->
|
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
|
|
|
</launch>
|