A minimal example of how to move a UR robot with the new Universal Robot ROS Driver. This package also includes some useful utilities to take care of common tasks such as running joint or cartesian waypoint trajectories.
- Clone this package to the
src
folder of your catkin workspace - In the root folder of your workspace, install dependencies:
rosdep install --from-paths src --ignore-src -r -y
- Build your workspace (
catkin_make
)
This package has some useful python objects you can import into your own nodes to send trajectories to the robot.
JointTrajectoryHandler
: Sends joint trajectories to the robot.- Choose between several UR ROS controllers:
scaled_pos_joint_traj_controller
,scaled_vel_joint_traj_controller
,pos_joint_traj_controller
,vel_joint_traj_controller
, andforward_joint_traj_controller
- You can also go to specific joint configurations via the
go_to_point()
function.
- Choose between several UR ROS controllers:
CartesianTrajectoryHandler
: Sends end effector pose trajectories to the robot.- Choose between several UR ROS controllers:
pose_based_cartesian_traj_controller
,joint_based_cartesian_traj_controller
, andforward_cartesian_traj_controller
- You can also go to specific cartesian poses via the
go_to_point()
function.
- Choose between several UR ROS controllers:
TwistHandler
: Sends cartesian end effector velocities to the robot.- This uses the
twist_controller
from the UR ROS controllers.
- This uses the
- (Teach Pendant) Turn on the robot, get into manual mode, then load the "EXTERNAL_CONTROL.urp" program.
- (Host Computer)
roslaunch ur_user_calibration bringup_armando.launch
- (Teach Pendant) Run the "EXTERNAL_CONTROL.urp" program.
- Set up a trajectory config (see config folder for examples)
roslaunch simple_ur_move run_joint_trajectory.launch traj:=test_traj_joint.yaml
Check out these launch files for information on different joint controllers you can use.
- Import necessary packages
import os
import rospkg
from simple_ur_move.joint_trajectory_handler import JointTrajectoryHandler
- Create a trajectory handler
traj_handler = JointTrajectoryHandler(
name="",
controller="scaled_pos_joint_traj_controller",
debug=False)
3a. Load the trajectory/config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="test_traj_joint.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
3b. OR Set trajectory config directly
config={TRAJECTORY CONFIG DICT}
traj_handler.set_config(config)
- Run the trajectory
traj_handler.set_initialize_time(3.0)
traj_handler.run_trajectory(blocking=True)
traj_handler.shutdown()
- Move directly to a point
point={'position',[0,0,0,0,0,0]} # Define the home configuration
traj_handler.set_initialize_time(3.0) # Set the transition time
traj_handler.go_to_point(point) # Go to the point
All together:
import os
import rospkg
from simple_ur_move.joint_trajectory_handler import JointTrajectoryHandler
# Create a trajectory handler
traj_handler = JointTrajectoryHandler(
name="",
controller="scaled_pos_joint_traj_controller",
debug=False)
# Load trajectory config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="test_traj_joint.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
# OR Set trajectory config directly
#config={TRAJECTORY CONFIG DICT}
#traj_handler.set_config(config)
# Run the trajectory
traj_handler.set_initialize_time(3.0)
traj_handler.run_trajectory(blocking=True)
traj_handler.shutdown()
# OR: Go directly to a single point
point={'position',[0,0,0,0,0,0]} # Define the home configuration
traj_handler.set_initialize_time(3.0) # Set the transition time here
traj_handler.go_to_point(point) # Go to the point
- Set up a trajectory config (see config folder for examples)
roslaunch simple_ur_move run_cartesian_trajectory.launch traj:=test_traj.yaml
roslaunch simple_ur_move run_cartesian_trajectory.launch traj:=pick_place.yaml
Check out these launch files for information on different cartesian controllers you can use.
- Import nessecary packages
import os
import rospkg
from simple_ur_move.cartesian_trajectory_handler import CartesianTrajectoryHandler
- Create a trajectory handler
traj_handler = CartesianTrajectoryHandler(
name="",
controller="pose_based_cartesian_traj_controller",
debug=False)
3a. Load the trajectory/config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="pick_place.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
3b. OR Set trajectory config directly
config={TRAJECTORY CONFIG DICT}
traj_handler.set_config(config)
- Run the trajectory
traj_handler.set_initialize_time(3.0)
traj_handler.run_trajectory(blocking=True)
traj_handler.shutdown()
- Move directly to a point
point={'position',[0.5, 0.5, 0.2]} # Define the point
traj_handler.set_initialize_time(3.0) # Set the transition time
traj_handler.go_to_point(point) # Go to the point
All together:
import os
import rospkg
from simple_ur_move.cartesian_trajectory_handler import CartesianTrajectoryHandler
# Create a trajectory handler
traj_handler = CartesianTrajectoryHandler(
name="",
controller="pose_based_cartesian_traj_controller",
debug=False)
# Load trajectory config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="pick_place.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
# OR Set trajectory config directly
#config={TRAJECTORY CONFIG DICT}
#traj_handler.set_config(config)
# Run the trajectory
traj_handler.set_initialize_time(3.0)
traj_handler.run_trajectory(blocking=True)
traj_handler.shutdown()
# OR: Go directly to a single point
point={'position',[0.5, 0.5, 0.2]} # Define the point
traj_handler.set_initialize_time(3.0) # Set the transition time here
traj_handler.go_to_point(point) # Go to the point
- Import nessecary packages
import os
import time
import rospkg
from simple_ur_move.twist_handler import TwistHandler
- Create a twist handler
traj_handler = TwistHandler(
name="",
debug=False)
3a. Load the config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="twist_config.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
3b. OR Set config directly
config={TRAJECTORY CONFIG DICT}
traj_handler.set_config(config)
- Set a twist of 5 mm/sec in the z-direction
traj_handler.set_speed_factor(1.0)
twist={'linear':[0,0,0.005], 'angular':[0,0,0]}
traj_handler.set_twist(twist)
time.sleep(4)
traj_handler.shutdown() # Sets speeds back to zero
All together:
import os
import time
import rospkg
from simple_ur_move.twist_handler import TwistHandler
# Create a twist handler
traj_handler = TwistHandler(
name="",
debug=False)
# Load config from a file
filepath_config = os.path.join(rospkg.RosPack().get_path('simple_ur_move'), 'config')
traj_file="twist_config.yaml"
traj_handler.load_config(filename=traj_file, directory=filepath_config)
# OR Set config directly
#config={TWIST CONFIG DICT}
#traj_handler.set_config(config)
# Set a twist of 5 mm/sec in the z-direction
traj_handler.set_speed_factor(1.0)
twist={'linear':[0,0,0.005], 'angular':[0,0,0]}
traj_handler.set_twist(twist)
time.sleep(4)
traj_handler.shutdown() # Sets speeds back to zero