ur_cb2 package

Submodules

ur_cb2.cb2_move_to_points module

A basic script to move to stored points for a cb2 robot.

Basic Usage: Store points using cb2_store_points.py (cb2-record from the terminal). Run this script, with commandline args.

ur_cb2.cb2_move_to_points.main()[source]

ur_cb2.cb2_robot module

Control sending and receiving of basic motion commands with a UR robot.

The module is designed to work with a CB2 robot running SW 1.8. This module only gives access to higher level commands. Lower level commands can be accessed through the cb2_send and cb2_receive modules.

class ur_cb2.cb2_robot.Goal(pose, cartesian, move_type, velocity=0.3, acceleration=1.3, radius=0.0)[source]

Bases: object

Holds movement goals

pose

A 6 float tuple or list describing the desired robot pose in either joint or cartesian coordinates

cartesian

A boolean describing whether the pose is in joint (False) or cartesian (True) space

move_type

A string describing the movement type. Valid values are: ‘linear’, ‘joint’, ‘process’

velocity

Float, the desired velocity for the specified move. For linear and process this is in m/s, for joint this is in rad/s

acceleration

Float, the desired velocity for the specified move. For linear and process this is in m/s^2, for joint this is in rad/s^2

radius

Float, the blend radius in m for bending moves. Note, a radius will result in inaccurate positioning and so the robot will never reach its goal.

__init__(pose, cartesian, move_type, velocity=0.3, acceleration=1.3, radius=0.0)[source]

Create a goal object.

Parameters:
  • pose (6 float tuple or list) – Describe the desired robot pose in either joint or cartesian coordinates
  • cartesian (boolean) – Describe whether the pose is in joint (False) or cartesian (True) space
  • move_type (string) – Describe the movement type. Valid values are: ‘linear’, ‘joint’, ‘process’
  • velocity (float) – The desired velocity for the specified move. For linear and process this is in m/s, for joint this is in rad/s
  • acceleration (float) – The desired velocity for the specified move. For linear and process this is in m/s^2, for joint this is in rad/s^2
  • radius (float) – The radius to use for bends. Note, a radius will result in inaccurate positioning and so the robot will never reach its goal.
Raises:

ValueError – The move type was not a valid value (‘linear’, ‘joint’, ‘process’)

class ur_cb2.cb2_robot.URRobot(ip, port, verbose=False)[source]

Bases: object

A class to roll up all communication with a UR robot.

Exposes some of the most commonly used commands made available by cb2_send and cb2_receive. To get full access to all commands, you will need to access those classes directly. The URRobot supports use by the with statement, and should be used as such, ex:

with URRobot(host, port) as robot:
    Do stuff...
__socket

socket.socket which is used to communicate with the robot

receiver

cb2_receive.URReceiver which receives data from the robot on a separate thread

sender

cb2_send.URSender which sends commands to the robot

error

Float which defines the error around a point from which it is acceptable to move to the next point.

goals

Queue.Queue of Goal objects defining movement goals

current_goal

Goal, the current movement goal.

__init__(ip, port, verbose=False)[source]

Construct a UR Robot connection to send commands

Parameters:
  • ip (str) – The IP address to find the Robot
  • port (int) – The port to connect to on the robot ( 3001:primary client, 3002:secondary client, 3003: real time client)
  • verbose (bool) – Whether to print information to the terminal
add_goal(goal)[source]

Adds a goal to the robots movement queue

Parameters:goal (Goal) – The goal to add to the queue
Raises:TypeError – A Goal was not passed in
at_goal()[source]

Return whether the robot is at the goal

Returns: Boolean, whether the robot is at its goal point

clear_goals()[source]

Clears the goal queue.

Allows a user to directly specify the next move.

is_stopped()[source]

Return whether the robot is stopped.

Returns: Boolean, whether the robot is stopped.

move_now(multiplier=None)[source]

Moves the robot.

Will immediately move the robot when called, cancelling out any other motions that may be in progress. The only caveat is that there is a time cost to this call in so far as that the TCP system can only send 125 packets per second. If you call move_now too often, it will queue up calls and not move now.

Parameters:multiplier (float) – An optional multiplier on the path goal which will make the robot move past the goal to allow better blending of moves. It is ignored if None.
move_on_error(multiplier=None)[source]

Moves the robot once the robot is within error of the next move.

Parameters:multiplier (float) – Defines how far the path should be set to overshoot, this can be useful for preventing deceleration between moves.
Raises:ValueError – The error value is not valid.
move_on_stop()[source]

Moves once the robot stops.

Note, the robot can be stopped both at the beginning and end of its path, therefore, this function also checks whether the robot is at its current goal.

sleep_time = 0.001

ur_cb2.cb2_robot_example module

A simple script demonstrating the basic usage of the cb2_robot class

ur_cb2.cb2_robot_example.main()[source]

Module contents