Skip to content
Snippets Groups Projects
Commit d343b540 authored by Jayant Khatkar's avatar Jayant Khatkar
Browse files

add launch files for easier connection steps to robot arms individually

parent a2c95fb8
Branches
No related merge requests found
......@@ -43,8 +43,9 @@ source ./catkin_ws/devel/setup.zsh
### Run the following 2 or 3 commands in separate tabs
# Connect to the UR5e and launch a controller service
roslaunch ur_robot_driver ur5e_bringup.launch robot_ip:=192.168.1.101 kinematics_config:=$(pwd)/calibrations/r1_cal.yaml
# NOTE: the IPs for our two arms are 192.168.1.101 and 192.168.1.103 - use r2_cal.yaml for second robot
roslaunch launch/r1_bringup.launch
# roslaunch launch/r2_bringup.launch #Cannot do both simultaneously
# NOTE: if the IPs change, add robot_ip:=xxxx to the end of the above commands
```
On the UR tablet do the following steps:
......@@ -58,9 +59,6 @@ On the UR tablet do the following steps:
```bash
# Launch MoveIt around the controller service
roslaunch ur5_e_moveit_config ur5_e_moveit_planning_execution.launch
# Optional: Launch RViz to Visualise the arm
roslaunch ur5_e_moveit_config moveit_rviz.launch config:=true
......
......@@ -6,7 +6,7 @@
<arg name="r2_robot_ip" default="192.168.1.103"/>
<group ns="r1">
<include file="$(find ur_robot_driver)/launch/r1_bringup.launch">
<include file="$(find ur_robot_driver)/launch/ur5e_bringup.launch">
<arg name="robot_ip" value="$(arg r1_robot_ip)"/>
<arg name="kinematics_config" value="$(arg r1_kinematics_config)"/>
</include>
......
<?xml version="1.0"?>
<launch>
<arg name="kinematics_config" default="$(find twins_utils)/calibrations/r1_cal.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="robot_ip" default="192.168.1.101"/>
<include file="$(find ur_robot_driver)/launch/ur5e_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
</include>
<include file="$(find ur5_e_moveit_config)/launch/ur5_e_moveit_planning_execution.launch"/>
</launch>
<?xml version="1.0"?>
<launch>
<arg name="kinematics_config" default="$(find twins_utils)/calibrations/r2_cal.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="robot_ip" default="192.168.1.103"/>
<include file="$(find ur_robot_driver)/launch/ur5e_bringup.launch">
<arg name="robot_ip" value="$(arg robot_ip)"/>
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
</include>
<include file="$(find ur5_e_moveit_config)/launch/ur5_e_moveit_planning_execution.launch"/>
</launch>
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