Commit d4604426 authored by Jayant Khatkar's avatar Jayant Khatkar

work towards simultaneously bringup, old bringup still works...

work towards simultaneously bringup, old bringup still works (twins-controller#5)
parent c955313a
Pipeline #1045 failed with stage
in 0 seconds
......@@ -45,7 +45,7 @@ r1_scaled_pos_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10
pos_traj_controller:
r1_pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints: *robot_joints
constraints:
......@@ -136,6 +136,6 @@ vel_traj_controller:
#stop_trajectory_duration: 0 # Defaults to 0.0
# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
r1_joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints: *robot_joints
......@@ -45,7 +45,7 @@ r2_scaled_pos_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10
pos_traj_controller:
r2_pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints: *robot_joints
constraints:
......@@ -136,6 +136,6 @@ vel_traj_controller:
#stop_trajectory_duration: 0 # Defaults to 0.0
# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
r2_joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints: *robot_joints
<?xml version="1.0"?>
<launch>
<arg name="r1_kinematics_config" default="$(find ur_e_description)/config/ur5e_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="r2_kinematics_config" default="$(find ur_e_description)/config/ur5e_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="r1_robot_ip" default="192.168.1.101"/>
<arg name="r2_robot_ip" default="192.168.1.103"/>
<group ns="frank">
<arg name="robot_ip" default="169.254.198.38"/>
<param name="robot_ip" value="$(arg robot_ip)"/>
<group ns="r1">
<include file="$(find ur_robot_driver)/launch/r1_bringup.launch">
<arg name="robot_ip" value="$(arg r1_robot_ip)"/>
<arg name="kinematics_config" value="$(arg r1_kinematics_config)"/>
</include>
</group>
<group ns="klaus">
<arg name="robot_ip" default="169.254.198.35"/>
<param name="robot_ip" value="$(arg robot_ip)"/>
<group ns="r2">
<include file="$(find ur_robot_driver)/launch/r2_bringup.launch">
<arg name="robot_ip" value="$(arg r2_robot_ip)"/>
<arg name="kinematics_config" value="$(arg r2_kinematics_config)"/>
</include>
</group>
</launch>
......@@ -6,7 +6,7 @@
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
<arg name="controllers" default="r1_scaled_pos_traj_controller" doc="Controllers that are activated by default."/>
<arg name="stopped_controllers" default="pos_traj_controller joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="stopped_controllers" default="r1_pos_traj_controller r1_joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/r1_ur5e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
<arg name="robot_description_file" default="$(find ur_e_description)/launch/ur5e_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur5e_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
......@@ -44,6 +44,7 @@
<arg name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
<arg name="tool_device_name" value="$(arg tool_device_name)"/>
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
<arg name="node_prefix" value="r1_"/>
</include>
</launch>
......@@ -6,7 +6,7 @@
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
<arg name="controllers" default="r2_scaled_pos_traj_controller" doc="Controllers that are activated by default."/>
<arg name="stopped_controllers" default="pos_traj_controller joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="stopped_controllers" default="r2_pos_traj_controller r2_joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/r2_ur5e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
<arg name="robot_description_file" default="$(find ur_e_description)/launch/ur5e_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur5e_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
......@@ -44,6 +44,7 @@
<arg name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
<arg name="tool_device_name" value="$(arg tool_device_name)"/>
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
<arg name="node_prefix" value="r2_"/>
</include>
</launch>
......@@ -21,6 +21,7 @@
<arg name="robot_description_file" doc="Robot description launch file."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<arg name="node_prefix" default="" doc="prefix for node name"/>
<!-- robot model -->
<include file="$(arg robot_description_file)">
......@@ -29,7 +30,7 @@
</include>
<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="$(arg node_prefix)robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<include file="$(find ur_robot_driver)/launch/ur_control.launch">
<arg name="debug" value="$(arg debug)"/>
......@@ -51,5 +52,6 @@
<arg name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
<arg name="tool_device_name" value="$(arg tool_device_name)"/>
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
<arg name="node_prefix" value="$(arg node_prefix)"/>
</include>
</launch>
......@@ -27,9 +27,10 @@
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<arg name="node_prefix" default="" doc="prefix for node name"/>
<!-- Load hardware interface -->
<node name="ur_hardware_interface" pkg="ur_robot_driver" type="ur_robot_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">
<node name="$(arg node_prefix)ur_hardware_interface" pkg="ur_robot_driver" type="ur_robot_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">
<param name="robot_ip" type="str" value="$(arg robot_ip)"/>
<param name="reverse_port" type="int" value="$(arg reverse_port)"/>
<param name="script_sender_port" type="int" value="$(arg script_sender_port)"/>
......@@ -50,7 +51,7 @@
</node>
<!-- Starts socat to bridge the robot's tool communication interface to a local tty device -->
<node if="$(arg use_tool_communication)" name="ur_tool_communication_bridge" pkg="ur_robot_driver" type="tool_communication" respawn="false" output="screen">
<node if="$(arg use_tool_communication)" name="$(arg node_prefix)ur_tool_communication_bridge" pkg="ur_robot_driver" type="tool_communication" respawn="false" output="screen">
<param name="robot_ip" value="$(arg robot_ip)"/>
<param name="reverse_port" type="int" value="$(arg reverse_port)"/>
<param name="script_sender_port" type="int" value="$(arg script_sender_port)"/>
......@@ -62,16 +63,16 @@
<rosparam file="$(arg controller_config_file)" command="load"/>
<!-- spawn controller manager -->
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
<node name="$(arg node_prefix)ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="$(arg controllers)" />
<!-- load other controller -->
<node name="ros_control_stopped_spawner" pkg="controller_manager" type="spawner" respawn="false"
<node name="$(arg node_prefix)ros_control_stopped_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="--stopped $(arg stopped_controllers)" />
<node name="controller_stopper" pkg="controller_stopper" type="node" respawn="false" output="screen">
<remap from="robot_running" to="ur_hardware_interface/robot_program_running"/>
<node name="$(arg node_prefix)controller_stopper" pkg="controller_stopper" type="node" respawn="false" output="screen">
<remap from="robot_running" to="$(arg node_prefix)ur_hardware_interface/robot_program_running"/>
<rosparam param="consistent_controllers">
- "joint_state_controller"
- "speed_scaling_state_controller"
......@@ -80,7 +81,7 @@
</node>
<!-- Make sure to start this in the namespace of the hardware interface -->
<node ns="ur_hardware_interface" name="ur_robot_state_helper" pkg="ur_robot_driver" type="robot_state_helper" respawn="false" output="screen">
<node ns="ur_hardware_interface" name="$(arg node_prefix)ur_robot_state_helper" pkg="ur_robot_driver" type="robot_state_helper" respawn="false" output="screen">
</node>
</launch>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment