mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Updated launch files
This commit is contained in:
@@ -15,30 +15,27 @@
|
|||||||
<arg name="limited" value="$(arg limited)"/>
|
<arg name="limited" value="$(arg limited)"/>
|
||||||
</include>
|
</include>
|
||||||
|
|
||||||
<group ns="universal_robot">
|
<!-- Load hardware interface -->
|
||||||
|
<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="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"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
<!-- Load hardware interface -->
|
<!-- Load controller settings -->
|
||||||
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="screen" launch-prefix="$(arg launch_prefix)">
|
<rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/>
|
||||||
<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"/>
|
|
||||||
</node>
|
|
||||||
|
|
||||||
<!-- Load controller settings -->
|
<!-- spawn controller manager -->
|
||||||
<rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/>
|
<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" />
|
||||||
|
|
||||||
<!-- spawn controller manager -->
|
<!-- load other controller -->
|
||||||
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
|
||||||
output="screen" args="joint_state_controller force_torque_sensor_controller velocity_based_position_trajectory_controller" />
|
output="screen" args="load position_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 -->
|
<!-- Convert joint states to /tf tranforms -->
|
||||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||||
</group>
|
|
||||||
|
|
||||||
</launch>
|
</launch>
|
||||||
|
|
||||||
|
|||||||
@@ -15,31 +15,29 @@
|
|||||||
<arg name="limited" value="$(arg limited)"/>
|
<arg name="limited" value="$(arg limited)"/>
|
||||||
</include>
|
</include>
|
||||||
|
|
||||||
<group ns="universal_robot">
|
|
||||||
|
|
||||||
<!-- 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)"/>
|
||||||
<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)"/>
|
||||||
<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"/>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- Load controller settings -->
|
<!-- Load controller settings -->
|
||||||
<rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/>
|
<rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/>
|
||||||
|
|
||||||
<!-- spawn controller manager -->
|
<!-- spawn controller manager -->
|
||||||
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
|
<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" />
|
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 -->
|
<!-- load other controller -->
|
||||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
|
||||||
|
output="screen" args="load position_based_position_trajectory_controller" />
|
||||||
|
|
||||||
</group>
|
<!-- Convert joint states to /tf tranforms -->
|
||||||
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
|
||||||
|
|
||||||
</launch>
|
</launch>
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user