klampt.control.robotinterfaceutils module
Contains utilities for the Klampt Robot Interface Layer.
The RobotInterfaceCompleter
class is extremely widely used to
standardize the capabilities of
RobotInterfaceBase
to handle
advanced functions. For example, if you have a position controlled robot
(e.g., an Arduino-controlled set of motors) and want to do more
sophisticated work with it, you can create a completer and get access to
motion queues, Cartesian control, collision filters, etc.
You can also assemble unified interfaces to robots composed of separate
independent parts via OmniRobotInterface
. For example, if you
have a robot arm + gripper, each working on separate physical interfaces,
creating an OmniRobotInterface will let you simultaneously control both.
Helper classes:
StepContext
: uses a Python context to guard beginStep()/endStep() pairs.
ThreadedRobotInterface
: adapts a synchronous interface to an asynchronous one via threading.
MultiprocessingRobotInterface
: adapts a synchronous interface to an asynchronous one via multiprocessing.
RobotInterfaceRecorder
: records or plays back commands to a RIL object.
Hints on wrapping to get the best performance:
RobotInterfaceCompleter sends immediate state queries and commands to the base interface, so it is more efficient than OmniRobotInterface when the base interface implements the given commands and queries.
OmniRobotInterface makes all state queries at the start of the step and delays sending the actual commands at the end of the step.
For asynchronous or client-server interfaces, the user has the choice of completing the base interface then wrapping it (e.g.,
ThreadedRobotInterface(RobotInterfaceCompleter(MyInterface)))
, or wrapping the base interface then completing it (e.g.,RobotInterfaceCompleter(ThreadedRobotInterface(MyInterface)))
. In the former case, more information is transmitted over the network, but the caller thread does less work. In the latter case, less information is transmitted, but the caller thread must do more work (including, for example, Cartesian control and collision detection.)Collision detection is usually the most computationally complex step. Configure your klamptModel’s geometries to be as simple as possible and set the trajectory collision checking to… TODO
This module also provides make_from_file()
which can either take a
.py / .pyc file, or a module string naming a Python file with a make
method.
Classes:
|
Makes it easier to handle exceptions in RIL control code. |
|
A RobotInterfaceBase that aggregates one or more parts, which are communicated with separately. |
|
Completes as much of the RobotInterfaceBase API as possible from a partially specified RobotInterfaceBase. |
|
Checks if the argument is in the range [qmin,qmax]. |
|
Checks if the argument (q,dq) can brake in time to stay within in the range [qmin,qmax]. |
|
Checks if the rotation is within some range and the translation is in the range [xmin,xmax]. |
|
Soft-stops if the robot at configuration q is in collision. |
|
Soft-stops if the robot at configuration q is in collision. |
|
Soft-stops if the difference between the two arguments exceed a threshold. |
|
Logs all the input items to fn, which is assumed by default to be a CSV file. |
|
Adapts a synchronous robot interface to an asynchronous robot interface that runs in a separate thread. |
|
Adapts a synchronous robot interface to an asynchronous robot interface that runs in a separate process. |
|
Emulates a fully-functional motion controller in software. |
|
A logger that will write parts of the RIL state to a CSV file. |
|
Records / playbacks all RIL commands to disk. |
Functions:
|
Create a RobotInterfaceBase from a Python file or module containing the |
|
Helper for implementers: an implementation of cartesianPosition that uses the Klampt model. |
|
Helper for implementers: an implementation of cartesianVelocity that uses the Klampt model. |
|
Helper for implementers: an implementation of cartesianForce that uses the Klampt model. |
- class klampt.control.robotinterfaceutils.StepContext(interface, ignore=False, silent=False)[source]
Bases:
object
Makes it easier to handle exceptions in RIL control code. Flags allow you to handle exceptions manually, print exceptions, or silence them completely.
- Parameters:
interface (RobotInterfaceBase) – the interface to step.
ignore (bool) – if False, raises the exception. Otherwise, prints an error message.
silent (bool) – if True, doesn’t print error messages if ignore=True.
- Members:
numExceptions (int): counts the # of exceptions raised
Usage:
interface = MyRobotInterface() interface.initialize() looper = TimedLooper(1.0/interface.controlRate()) #declare context outside of loop so numExceptions can be counted context = StepContext(interface,ignore=True) while looper: with context: interface.setCartesianPosition([0.4]) #incorrect arguments, exceptions will be printed if context.numExceptions > 10: print("Breaking loop, too many exceptions.") looper.stop()
- klampt.control.robotinterfaceutils.make_from_file(fn, robotModel, *args, **kwargs)[source]
Create a RobotInterfaceBase from a Python file or module containing the
make()
function.args and kwargs will be passed to
make
.- Return type:
- Example::
iface = make_from_file(‘klampt.control.simrobotcontroller’, robot)
- class klampt.control.robotinterfaceutils.OmniRobotInterface(klamptModel=None)[source]
Bases:
_RobotInterfaceStatefulBase
A RobotInterfaceBase that aggregates one or more parts, which are communicated with separately. For example, a mobile manipulator can consist of a base, arms, and grippers.
On startup, call
addPhysicalPart(name,driver_indices,interface)
for each part of the robot.driver_indices
must correspond to the indices of drivers corresponding to that part in the Klamp’t model.The total configuration for the robot is a list of floats, segmented into physical parts. The ordering of the parts’ configurations, velocities, etc is given by the driver_indices as they were added.
Allows for complex arrangements like a physical part that has sub-parts, such as an arm with an integrated gripper handled with the same physical interface. Sub-parts are named ‘PARENT__CHILD’.
TODO: handle more than one layer of nesting.
For example, if you want to assemble a unified interface / klamptModel from two interfaces, with part2 (e.g., a gripper) mounted on part1 (e.g., an arm), you’d run:
voltron_controller = OmniRobotInterface(klampt_model) voltron_controller.addPhysicalPart("part1",part1_interface,part1_indices) voltron_controller.addPhysicalPart("part2",part2_interface,part2_indices) if not voltron_controller.initailize(): print("hmm... error on initialize?") ... do stuff, treating voltron_controller as a unified robot ...
If you have separate parts with their own Klamp’t models, and wish to dynamically construct a unified model, you may use the
mount
command as follows:world = WorldModel() world.readFile(part1_interface.properties['klamptModelFile']) world.readFile(part2_interface.properties['klamptModelFile']) part1_model = world.robot(0) part2_model = world.robot(1) ee_link = part1_model.numLinks()-1 mount_rotation = ... some so3 element... mount_translation = ... some translation vector... part1_model.mount(ee_link,part2_model,mount_rotation,mount_translation) #part1 model is now the whole robot world.remove(part2_model) #not strictly necessary to remove the model from the world... klampt_model = world.robot(0) part1_indices = list(range(part1_model.numDrivers())) part2_indices = list(range(part1_model.numDrivers(),part1_model.numDrivers()+part2_model.numDrivers())) #code above should follow
If your robot has a RobotInfo structure associated with it, you’d point its
controllerFile
attribute to a file containing code like:from klampt.control.robotinterfaceutils import OmniRobotInterface #import Part1RobotInterface and Part2RobotInterface from somewhere def make(robotModel): voltron_controller = OmniRobotInterface(robotModel) part1_controller = Part1RobotInterface() part2_controller = Part2RobotInterface() n1 = part1_controller.numJoints() n2 = part2_controller.numJoints() assert n1 + n2 == robotModel.numDrivers() voltron_controller.addPhysicalPart("part1",part1_controller,list(range(n1))) voltron_controller.addPhysicalPart("part2",part2_controller,list(range(n1,n1+n2))) #add any virtual parts if your RobotInfo defines them return voltron_controller
Methods:
addPhysicalPart
(name, interface[, indices])Adds a new part corresponding to a physical RIL implementation.
addVirtualPart
(name, indices)- rtype:
None
setFilter
(name, filter[, input, output])Enables or disables a filter.
setPartFilter
(part, name, filter[, input, ...])- rtype:
None
setJointLimits
([qmin, qmax, op])Activates a joint limit filter.
setPartJointLimits
(part[, qmin, qmax, op])Activates a joint limit filter.
setCollisionFilter
([world, op])Activates a collision filter.
Tries to connect to the robot.
This is called before the commands sent at each time step
endStep
()This is called after the commands sent at each time step
partInterface
(part[, joint_idx])Returns a RobotInterfaceBase that allows control of the given part/joint.
reset
()If the robot has a non-normal status code, attempt to reset it to normal operation.
- addPhysicalPart(name, interface, indices=None)[source]
Adds a new part corresponding to a physical RIL implementation.
If klamptModel was not provided to the initializer, then this part will be appended to the list of parts, and indices=None is allowed. Otherwise, indices needs to be a list of driver indices corresponding to the part in klamptModel.
- Return type:
None
- setFilter(name, filter, input='auto', output='auto')[source]
Enables or disables a filter. The filter is attached to the given name, which can be a standard filter item or sensor.
Standard filters include: :rtype:
None
‘joint_limit’: adjusts position commands
‘velocity_limit’: adjusts velocity commands
‘acceleration_limit’: adjusts acceleration commands
‘torque_limit’: adjusts torque commands
‘tracking_monitor’: monitors sensed vs commanded positions
‘self_collision’: adjusts position commands to avoid collisions
‘obstacle_collision’: adjusts position commands to avoid collisions
SENSOR_NAME: some sensor for which
hasSensor(SENSOR_NAME)=True
.
Valid operands include:
‘sensedPosition’, ‘sensedVelocity’, ‘sensedAcceleration’, and ‘sensedTorque’: updated on every time step
‘commandedPosition’, ‘commandedVelocity’, ‘commandedAcceleration’, and ‘commandedTorque’: updated on every time step
‘positionCommand’, ‘velocityCommand’, ‘torqueCommand’: updated when a position, velocity, or torque command are scheduled for sending to the robot.
SENSOR_NAME: some sensor for which
hasSensor(SENSOR_NAME)=True
.‘status’: the input / output status
- Parameters:
name (str) – the filter identifier
filter (Callable, or None) –
the filter operator. If None, disables the filter.
Otherwise, the filter is callable and takes #inputs arguments (usually 1) and returns #outputs arguments to be stored in the output (a tuple if #outputs > 1).
Note that to implement a stateful filter, you would create a class that updates internal state on __call__. RobotInterfaceCompleter also accepts
klampt.control.blocks.Block
objects.input (str or list of str) – one or more input operands. If ‘auto’, the input operands are auto-determined from the name.
output (str or list of str) – one or more output operands. If ‘auto’, the output operands are auto-determined from the name.
- setJointLimits(qmin='auto', qmax='auto', op='clamp')[source]
Activates a joint limit filter.
If qmin/qmax are ‘auto’, these are read from the klampt robot model or the properties.
If op is…
‘clamp’ then commands are silently clamped to their limits.
‘stop’ a soft-stop is raised.
‘warn’ a warning is printed and the robot silently ignores the command.
- setPartJointLimits(part, qmin='auto', qmax='auto', op='clamp')[source]
Activates a joint limit filter.
If qmin/qmax are ‘auto’, these are read from the klampt robot model or the properties.
If op is…
‘clamp’ then commands are silently clamped to their limits.
‘stop’ a soft-stop is raised.
‘warn’ a warning is printed and the robot silently ignores the command.
- setCollisionFilter(world=None, op='warn')[source]
Activates a collision filter.
If world=None, only does self collision. Otherwise, does self and world collision.
If op = ‘stop’, a soft stop is raised if a collision is predicted.
If op = ‘warn’, a warning is printed and the robot silently ignores the command.
- initialize()[source]
Tries to connect to the robot. Returns true if ready to send commands. This should probably be the first method called.
- Return type:
bool
- class klampt.control.robotinterfaceutils.RobotInterfaceCompleter(base_interface, base_initialized=False)[source]
Bases:
RobotInterfaceBase
Completes as much of the RobotInterfaceBase API as possible from a partially specified RobotInterfaceBase. For example, if your RobotInterfaceBase implements position control, then the Completer will provide velocity, piecewise linear, and piecewise cubic, and Cartesian control commands.
At a minimum, a base must implement
sensedPosition()
and one of the following:This class will not emulate:
Any sensors
setSetting()
and getSetting
It will emulate:
Clock time from control rate using integration
Control rate from clock time using differences
Joint velocities from joint positions using finite differences
Joint positions from joint velocities using integration
PID control from torque commands
Torque commands from PID control
Piecewise linear / piecewise cubic control from position / velocity / PID control.
Cartesian positions / velocities / forces from joint positions / velocities / torques using the Klamp’t model.
Cartesian control using the Klamp’t model and IK
Optional safety checks (joint limits, velocity limits, discontinuous commands, and tracking errors)
E-stopping and soft stopping requiring reset.
Note
The base interface’s klamptModel() method must be implemented for Cartesian control and acceleration-bounded control to work properly.
- Parameters:
base_interface (RobotInterfaceBase) – the partially-implemented interface.
base_initialized (bool, optional) – if True, initialize() will not initialize the base.
Methods:
numJoints
([part])Returns the number of joints of the given part.
parts
()Returns a dictionary of (part-name,configuration index list) pairs defining the named parts of the robot.
addPart
(name, indices)Can add new parts, e.g., for Cartesian control.
Tries to connect to the robot.
close
()Cleanly shuts down any resources acquired using initialize().
Deprecated.
This is called before the commands sent at each time step
endStep
()This is called after the commands sent at each time step
Returns the control rate, in Hz
clock
()Returns the current time on the robot's clock, in seconds
estop
()Requires reset
softStop
()Requires reset
reset
()If the robot has a non-normal status code, attempt to reset it to normal operation.
setSetting
(key, value)Sets an implementation-dependent setting.
getSetting
(key)Retrieves an implementation-dependent setting.
partInterface
(part[, joint_idx])Returns a RobotInterfaceBase that allows control of the given part/joint.
jointName
(joint_idx)Returns a string naming the given joint
setControlMode
(mode, *args, **kwargs)Enables a custom control mode.
functionCall
(proc, *args, **kwargs)Enables a custom one-off function call.
setFilter
(name, filter[, input, output])Enables or disables a filter.
setJointLimits
([qmin, qmax, op])Activates a joint limit filter.
setCollisionFilter
([world, op])Activates a collision filter.
sensors
()Returns a list of names of possible sensors on this robot.
Returns a list of names of enabled sensors on this robot.
hasSensor
(sensor)Returns true if the given sensor can be enabled.
enableSensor
(sensor)Enables / disables a sensor.
sensorMeasurements
(sensor)Returns the latest measurements from a sensor.
sensorUpdateTime
(sensor)Returns the clock time of the last sensor update.
setPosition
(q)Sets an instantaneous position command.
setVelocity
(v[, ttl])Sets an instantaneous velocity command.
setTorque
(t[, ttl])Sets a instantaneous torque command.
setPID
(q, dq[, t])Sets a PID command to configuration q, velocity dq, and feedforward torque t.
setPIDGains
(kP, kI, kD)Sets the PID gains.
Gets the PID gains (kP,kI,kD) as set to a prior call to setPIDGains.
moveToPosition
(q[, speed])Sets a move-to position command.
setPiecewiseLinear
(ts, qs[, relative])Tells the robot to start a piecewise linear trajectory command.
setPiecewiseCubic
(ts, qs, vs[, relative])Tells the robot to start a piecewise cubic trajectory command.
setToolCoordinates
(xtool_local)Sets the tool coordinates of this robot relative to its end effector link.
Gets the tool coordinates of this robot relative to its end effector link.
setGravityCompensation
([gravity, load, load_com])Sets up gravity compensation with a given gravity vector and end effector load.
Gets (gravity,load,load_com) as from a prior call to setGravityCompensation.
setCartesianPosition
(xparams[, frame])Sets a Cartesian position command.
moveToCartesianPosition
(xparams[, speed, frame])Sets a Cartesian move-to-position command.
moveToCartesianPositionLinear
(xparams[, ...])Sets a Cartesian move-to-position command.
setCartesianVelocity
(dxparams[, ttl, frame])Sets a Cartesian velocity command.
setCartesianForce
(fparams[, ttl, frame])Sets a Cartesian torque command.
status
([joint_idx])Returns a status string for the robot / given joint.
isMoving
([joint_idx])Returns true if the robot / joint are currently moving
Retrieves the currently sensed joint position.
Retrieves the currently sensed joint velocity.
Retrieves the currently sensed joint torque.
Retrieves the currently commanded joint position.
Retrieves the currently commanded joint velocity.
Retrieves the currently commanded joint torque.
Retrieves the destination of a motion queue controller.
Retrieves the final velocity of a motion queue controller.
Retrieves the final clock time of a motion queue controller.
stateValue
(name)Retrieves some custom state value
cartesianPosition
(q[, frame])Converts from a joint position vector to a cartesian position.
cartesianVelocity
(q, dq[, frame])Converts from a joint position / velocity vector to a cartesian velocity.
cartesianForce
(q, t[, frame])Converts from a joint position / torque vector to a cartesian force.
sensedCartesianPosition
([frame])sensedCartesianVelocity
([frame])sensedCartesianForce
([frame])commandedCartesianPosition
([frame])commandedCartesianVelocity
([frame])commandedCartesianForce
([frame])destinationCartesianPosition
([frame])Retrieves the Cartesian destination of a motion queue controller.
destinationCartesianVelocity
([frame])Retrieves the final Cartesian velocity of a motion queue controller.
partToRobotConfig
(pconfig, part, robotConfig)Fills a configuration vector for the whole robot given the configuration pconfig for a part
If applicable, returns the Klamp't RobotModel associated with this controller.
configFromKlampt
(klamptConfig[, part, joint_idx])Extracts a RobotInterfaceBase configuration from a configuration of the Klampt model.
velocityFromKlampt
(klamptVelocity[, part, ...])Extracts a RobotInterfaceBase velocity from a velocity of the Klampt model.
configToKlampt
(config[, klamptConfig, part, ...])Creates a configuration vector for the Klamp't model using the RobotInterfaceBase configuration.
velocityToKlampt
(velocity[, klamptVelocity, ...])Creates a velocity vector for a Klamp't model using the joint velocity.
- numJoints(part=None)[source]
Returns the number of joints of the given part. By default, this returns the number of actuated DOFs in the Klamp’t model.
- parts()[source]
Returns a dictionary of (part-name,configuration index list) pairs defining the named parts of the robot.
Since this will be used a lot, make sure to declare your override with @functools.lru_cache.
- addPart(name, indices)[source]
Can add new parts, e.g., for Cartesian control.
As an example, suppose we’ve created a RobotInterfaceCompleter for a 6DOF robot with 1DOF gripper, with the base controller using position control of all 7 DOFs. We can then create an arm and a gripper via:
robotinterface.addPart("arm",list(range(6))) robotinterface.addPart("gripper",[6]) #start moving the arm upward robotinterface.partInterface("arm").setCartesianVelocity([0,0,0],[0,0,0.1])
- initialize()[source]
Tries to connect to the robot. Returns true if ready to send commands. This should probably be the first method called.
- reset()[source]
If the robot has a non-normal status code, attempt to reset it to normal operation. The caller should poll until status()==’ok’
- partInterface(part, joint_idx=None)[source]
Returns a RobotInterfaceBase that allows control of the given part/joint. If no such controller exists, raises a NotImplementedError.
The part/joint controller should operate on exactly the DOFs specified by self.indices(part,joint_idx).
- setFilter(name, filter, input='auto', output='auto')[source]
Enables or disables a filter. The filter is attached to the given name, which can be a standard filter item or sensor.
Standard filters include: :rtype:
None
‘joint_limit’: adjusts position commands
‘velocity_limit’: adjusts velocity commands
‘acceleration_limit’: adjusts acceleration commands
‘torque_limit’: adjusts torque commands
‘tracking_monitor’: monitors sensed vs commanded positions
‘self_collision’: adjusts position commands to avoid collisions
‘obstacle_collision’: adjusts position commands to avoid collisions
SENSOR_NAME: some sensor for which
hasSensor(SENSOR_NAME)=True
.
Valid operands include:
‘sensedPosition’, ‘sensedVelocity’, ‘sensedAcceleration’, and ‘sensedTorque’: updated on every time step
‘commandedPosition’, ‘commandedVelocity’, ‘commandedAcceleration’, and ‘commandedTorque’: updated on every time step
‘positionCommand’, ‘velocityCommand’, ‘torqueCommand’: updated when a position, velocity, or torque command are scheduled for sending to the robot.
SENSOR_NAME: some sensor for which
hasSensor(SENSOR_NAME)=True
.‘status’: the input / output status
- Parameters:
name (str) – the filter identifier
filter (Callable, or None) –
the filter operator. If None, disables the filter.
Otherwise, the filter is callable and takes #inputs arguments (usually 1) and returns #outputs arguments to be stored in the output (a tuple if #outputs > 1).
Note that to implement a stateful filter, you would create a class that updates internal state on __call__. RobotInterfaceCompleter also accepts
klampt.control.blocks.Block
objects.input (str or list of str) – one or more input operands. If ‘auto’, the input operands are auto-determined from the name.
output (str or list of str) – one or more output operands. If ‘auto’, the output operands are auto-determined from the name.
- setJointLimits(qmin='auto', qmax='auto', op='clamp')[source]
Activates a joint limit filter.
If qmin/qmax are ‘auto’, these are read from the klampt robot model or the properties.
If op is…
‘clamp’ then commands are silently clamped to their limits.
‘stop’ a soft-stop is raised.
‘warn’ a warning is printed and the robot silently ignores the command.
- setCollisionFilter(world=None, op='warn')[source]
Activates a collision filter.
If world=None, only does self collision. Otherwise, does self and world collision.
If op = ‘stop’, a soft stop is raised if a collision is predicted.
If op = ‘warn’, a warning is printed and the robot silently ignores the command.
- sensorMeasurements(sensor)[source]
Returns the latest measurements from a sensor. Interpretation of the result is sensor-dependent.
- setPosition(q)[source]
Sets an instantaneous position command.
- Parameters:
q (list of floats) – A list of floats giving the desired configuration of the robot.
- setVelocity(v, ttl=None)[source]
Sets an instantaneous velocity command.
- Parameters:
v (list of floats) – A list of floats giving the desired velocity of each joint.
ttl (float, optional) – A time-to-live for this command.
- setTorque(t, ttl=None)[source]
Sets a instantaneous torque command.
- Parameters:
t (list of floats) – A list of floats giving the desired torques at each joint.
ttl (float, optional) – A time-to-live for this command.
- setPID(q, dq, t=None)[source]
Sets a PID command to configuration q, velocity dq, and feedforward torque t.
- setPIDGains(kP, kI, kD)[source]
Sets the PID gains. Some controllers might not implement this even if they implement setPID…
- getPIDGains()[source]
Gets the PID gains (kP,kI,kD) as set to a prior call to setPIDGains. Some controllers might not implement this even if they implement setPIDGains…
- moveToPosition(q, speed=1)[source]
Sets a move-to position command. The trajectory that the robot will take on should be extractable through getMoveToTrajectory(q).
- Parameters:
q (list of floats) – A list of floats giving the desired configuration of the robot.
speed (float, optional) – The speed at which the position should be reached.
- setPiecewiseLinear(ts, qs, relative=True)[source]
Tells the robot to start a piecewise linear trajectory command. The first milestone will be interpolated from the current commanded configuration.
- Parameters:
ts (list of floats) – times of the trajectory’s milestones
qs (list of floats, or list of list of floats) – list of the trajectory’s milestones
relative (bool) – if true, the times in ts are assumed to start at current time 0. Otherwise, they must all be greater than the current time retrieved by clock().
- setPiecewiseCubic(ts, qs, vs, relative=True)[source]
Tells the robot to start a piecewise cubic trajectory command. The first milestone will be interpolated from the current commanded configuration / velocity.
- Parameters:
ts (list of floats) – times of the trajectory’s milestones
qs (list of floats, or list of list of floats) – list of the trajectory’s milestones
vs (list of floats, or list of list of floats) – list of the trajectory’s derivatives at the milestones.
relative (bool) – if true, the times in ts are assumed to start at current time 0. Otherwise, they must all be greater than the current time retrieved by clock().
- setToolCoordinates(xtool_local)[source]
Sets the tool coordinates of this robot relative to its end effector link.
- getToolCoordinates()[source]
Gets the tool coordinates of this robot relative to its end effector link.
- setGravityCompensation(gravity=[0, 0, -9.8], load=0.0, load_com=[0, 0, 0])[source]
Sets up gravity compensation with a given gravity vector and end effector load.
- Parameters:
gravity (list of 3 floats, optional) – the gravity vector in the base frame, in m/s^2.
load (float, optional) – a weight attached to the end effector, in kg.
load_com (list of 3 floats, optional) – the COM of the load, expressed relative to the end-effector link frame.
- getGravityCompensation()[source]
Gets (gravity,load,load_com) as from a prior call to setGravityCompensation.
- setCartesianPosition(xparams, frame='world')[source]
Sets a Cartesian position command. The tool is commanded to reach the given coordinates relative to the given frame. Like setPosition, this command is sent in immediate mode.
- Parameters:
xparams – a klampt.math.se3 object for position / orientation
position-only. (commands, or a 3-vector for) –
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- moveToCartesianPosition(xparams, speed=1.0, frame='world')[source]
Sets a Cartesian move-to-position command. The tool is commanded to reach the given coordinates relative to the given frame. The movement is accomplished via an arbitrary joint space motion, and is not necessarily linear in Cartesian space.
- Parameters:
xparams – typically a klampt.math.se3 object for position / orientation commands, or a 3-vector for position-only.
speed (float, optional) – The speed at which the position should be reached.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- moveToCartesianPositionLinear(xparams, speed=1.0, frame='world')[source]
Sets a Cartesian move-to-position command. The tool is commanded to reach the given coordinates relative to the given frame via a linear Cartesian path.
- Parameters:
xparams – typically a klampt.math.se3 object for position / orientation commands, or a 3-vector for position-only.
speed (float, optional) – The speed at which the position should be reached.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- setCartesianVelocity(dxparams, ttl=None, frame='world')[source]
Sets a Cartesian velocity command. The tool is commanded to move along the given velocity(s) relative to the given frame.
- Parameters:
dxparams – typically an (angular velocity, translational velocity) pair for translation / orientation commands. A 3-vector for translation-only.
ttl (float, optional) – A time-to-live for this command.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- setCartesianForce(fparams, ttl=None, frame='world')[source]
Sets a Cartesian torque command. The tool is commanded to exert the given force or (torque, force) relative to the given frame.
- Parameters:
fparams – typically an (torque, force) pair for translation / orientation commands. A 3-vector for translation-only.
ttl (float, optional) – A time-to-live for this command.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- status(joint_idx=None)[source]
Returns a status string for the robot / given joint. ‘ok’ means everything is OK.
- cartesianPosition(q, frame='world')[source]
Converts from a joint position vector to a cartesian position.
- Parameters:
q (vector) – the (whole) robot’s joint positions.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’. Note: ‘end effector’ and ‘tool’ don’t make any sense here, since the tool frame is constant relative to these frames…
- Returns:
specifies end effector Cartesian transform relative to the given frame.
- Return type:
Klampt se3 element
- cartesianVelocity(q, dq, frame='world')[source]
Converts from a joint position / velocity vector to a cartesian velocity.
- Parameters:
q (vector) – the (whole) robot’s joint positions.
dq (vector) – the (whole) robot’s joint velocities.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’. Note: if ‘base’ is specified, the velocity of the base is subtracted from the reported speed.
- Returns:
specifies end effector Cartesian angular velocity/velocity relative to the given frame.
- Return type:
(w,v)
- cartesianForce(q, t, frame='world')[source]
Converts from a joint position / torque vector to a cartesian force.
- Parameters:
q (vector) – the (whole) robot’s joint positions.
t (vector) – the (whole) robot’s joint torques.
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’.
- Returns:
specifies end effector Cartesian torque/force relative to given frame.
- Return type:
(t,f)
- destinationCartesianPosition(frame='world')[source]
Retrieves the Cartesian destination of a motion queue controller.
- Parameters:
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- destinationCartesianVelocity(frame='world')[source]
Retrieves the final Cartesian velocity of a motion queue controller.
- Parameters:
frame (str) – either ‘world’, ‘base’, ‘end effector’, or ‘tool’
- partToRobotConfig(pconfig, part, robotConfig)[source]
Fills a configuration vector for the whole robot given the configuration pconfig for a part
- klamptModel()[source]
If applicable, returns the Klamp’t RobotModel associated with this controller. Default tries to load from properties[‘klamptModelFile’].
Note that the configuration DOFs in the RIL robot correspond to the robot’s DRIVERs, not its links.
Note: the result of the default implementation is cached, so this can be called multiple times without a performance hit.
- configFromKlampt(klamptConfig, part=None, joint_idx=None)[source]
Extracts a RobotInterfaceBase configuration from a configuration of the Klampt model.
Note: the configuration of the model in self.klamptModel() is overridden.
- velocityFromKlampt(klamptVelocity, part=None, joint_idx=None)[source]
Extracts a RobotInterfaceBase velocity from a velocity of the Klampt model.
- configToKlampt(config, klamptConfig=None, part=None, joint_idx=None)[source]
Creates a configuration vector for the Klamp’t model using the RobotInterfaceBase configuration.
If klamptConfig is given, then these values are used for the non-part configuration values. Otherwise, the robot’s current configuration from self.klamptModel() is used.
Note
The configuration of the model in self.klamptModel() is overridden.
- velocityToKlampt(velocity, klamptVelocity=None, part=None, joint_idx=None)[source]
Creates a velocity vector for a Klamp’t model using the joint velocity.
If klamptVelocity is given, then these values are used for the non-part configuration values. Otherwise, the robot’s current velocity from self.klamptModel() is used.
Note
The velocity of the model in self.klamptModel() is overridden.
- class klampt.control.robotinterfaceutils.LimitFilter(op, qmin, qmax)[source]
Bases:
object
Checks if the argument is in the range [qmin,qmax]. Can either clamp to range silently, warn, or perform a stop.
- class klampt.control.robotinterfaceutils.BrakeLimitFilter(op, qmin, qmax, amin, amax)[source]
Bases:
object
Checks if the argument (q,dq) can brake in time to stay within in the range [qmin,qmax]. Can either clamp dq to range silently, warn, or perform a stop.
- class klampt.control.robotinterfaceutils.CartesianLimitFilter(op, Rref, rpymin, rpymax, xmin, xmax)[source]
Bases:
object
Checks if the rotation is within some range and the translation is in the range [xmin,xmax]. The rotation range is so3.rpy(Rref^T R) in [rpymin,rpymax].
Can set Rref,rpymin,rpymax to None to turn off rotation range checking, and set xmin,xmax to None to turn off translation range checking.
Can either clamp to range silently, warn, or perform a stop.
- class klampt.control.robotinterfaceutils.SelfCollisionFilter(op, robot)[source]
Bases:
object
Soft-stops if the robot at configuration q is in collision.
- class klampt.control.robotinterfaceutils.CollisionFilter(op, robot, obstacles)[source]
Bases:
object
Soft-stops if the robot at configuration q is in collision.
- class klampt.control.robotinterfaceutils.DifferenceFilter(op, threshold, norm=inf)[source]
Bases:
object
Soft-stops if the difference between the two arguments exceed a threshold. Returns 0 arguments.
Methods:
advance
(q1, q2)
- class klampt.control.robotinterfaceutils.LoggingFilter(fn, items, delim=',', header=True)[source]
Bases:
Block
Logs all the input items to fn, which is assumed by default to be a CSV file.
Methods:
advance
(*args)Computes the output of this controller given an argument list, and advances the time step.
- klampt.control.robotinterfaceutils.klamptCartesianPosition(model, q, part_indices, tool_coordinates, frame)[source]
Helper for implementers: an implementation of cartesianPosition that uses the Klampt model.
- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]- Parameters:
robot (RobotModel) – the Klampt model
q – configuration for whole robot (#drivers)
part_indices – the driver indices of the part being queried.
tool_coordinates – the local coordinates of the tool point
frame – either ‘world’ or ‘base’
- klampt.control.robotinterfaceutils.klamptCartesianVelocity(model, q, dq, part_indices, tool_coordinates, frame)[source]
Helper for implementers: an implementation of cartesianVelocity that uses the Klampt model.
- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]- Parameters:
q – configuration for whole robot (#drivers)
dq – velocity for whole robot (#drivers)
part_indices – the driver indices of the part being queried.
tool_coordinates – the local coordinates of the tool point
frame – either ‘world’ or ‘base’
- klampt.control.robotinterfaceutils.klamptCartesianForce(model, q, t, part_indices, tool_coordinates, frame)[source]
Helper for implementers: an implementation of cartesianForce that uses the Klampt model.
- Parameters:
q – configuration for whole robot (#drivers)
t – torques for whole robot (#drivers)
part_indices – the driver indices of the part being queried.
tool_coordinates – the local coordinates of the tool point
frame – either ‘world’ or ‘base’
- class klampt.control.robotinterfaceutils.ThreadedRobotInterface(interface)[source]
Bases:
_RobotInterfaceStatefulBase
Adapts a synchronous robot interface to an asynchronous robot interface that runs in a separate thread.
There is no need to run beginStep() and endStep() on this interface.
All query functions will return the results from the prior time step.
All commands are queued, with execution delayed until the next time step.
Methods:
log
(msg)Override this to change thread warning prints
Tries to connect to the robot.
close
()Cleanly shuts down any resources acquired using initialize().
- class klampt.control.robotinterfaceutils.MultiprocessingRobotInterface(interface)[source]
Bases:
_RobotInterfaceStatefulBase
Adapts a synchronous robot interface to an asynchronous robot interface that runs in a separate process.
There is no need to run beginStep() and endStep() on this interface.
All query functions will return the results from the prior time step.
All commands are queued, with execution delayed until the next time step.
Methods:
log
(msg)Override this to change thread warning prints
Tries to connect to the robot.
close
()Cleanly shuts down any resources acquired using initialize().
- class klampt.control.robotinterfaceutils.RobotInterfaceEmulator(nd, klamptModel)[source]
Bases:
object
Emulates a fully-functional motion controller in software. All motion commands and queries are available, but the caller must always specify which indices are being used. Most prominently used in
RobotInterfaceCompleter
andOmniRobotInterface
Joint control usage:
interface = MyRobotInterfaceBase() emulator = RobotInterfaceEmulator(interface.numJoints(),klampt_model) interface.beginStep() qcmd = interface.commandedPosition() #query current configuration interface.endStep() emulator.initCommand(qcmd,[0]*len(qcmd),None) #initialize with current commanded values move_to_sent = False while True: t = interface.clock() emulator.advanceClock(t,None) #can also advance by rate q,v = interface.sensedPosition(),interface.sensedVelocity() emulator.update(q,v) if not move_to_sent: part1_indices = [0,1,4,5] # whatever indices are available part1_config = [0.4,0.3,-0.2,0.5] emulator.moveTo(part1_indices,part1_config) #begins a move-to-command part2_indices = [2,3] # some other indices part2_velocity = [0.1,0.3] emulator.setVelocity(part2_indices,part2_velocity,1.5) #begins a velocity command for 1.5s move_to_sent = True #after the first step, the emulator will generate position commands that execute the move-to q = emulator.getCommand('setPosition') #argument is the desired command type interface.setPosition(q) emulator.onBaseCommand('setPosition','setPosition') #indicates that we successfully executed that command type
To minimize the number of instructions sent to the interface or to dispatch to different command types in the base interface:
dcm = emulator.desiredControlMode() if dcm is not None: #desiredControlMode() returns None if done with sending, q = emulator.getCommand('setPosition') #argument is the desired command type interface.setPosition(q) #send to the actual controller emulator.onBaseCommand(dcm,'setPosition') #indicates that we successfully executed that command type
Note that setPosition and setVelocity are always available as command types.
To run Cartesian control:
#setup six_dof_indices = [0,1,2,3,4,5] tool_coords = (0,0,0.1) emulator.setToolCoordinates(six_dof_indices,tool_coords) while True: ... #do standard emulator setup if do_cartesian_move: #read transform and send a move to target_shift = [0.2,0,0] Tcmd = emulator.commandedCartesianPosition(six_dof_indices) Ttarget = (Tcmd[0],vectorops.add(Tcmd[0],target_shift) emulator.moveToCartesianPosition(six_dof_indices,Ttarget) do_cartesian_move = False ... #do standard emulator command generation. The emulator will solve for IK automatically.
Attributes:
Methods:
initialize
(qsns, vsns, tsns, qcmd, vcmd, tcmd)Could be called before the emulator starts running to initialize the commanded joint positions before the emulator takes over.
advanceClock
(newClock, rate)update
(q, v)Advances the interface with the sensed config q and sensed velocity v.
sendToInterface
(interface[, indices])Sends a command to the interface using the highest level interface as possible.
desiredControlMode
([indices])Returns the highest level control mode requested of the joints.
getCommand
(commandType[, indices])Retrieves the args for the command to be sent to the actual interface on this time step.
onBaseCommand
(desiredControlMode, ...[, indices])To be called when the completer has decided which base control mode to use.
promote
(indices, controlType)To accept commands of the given controlMode, switches over the current state to the controlMode
setFilter
(indices, name, filter[, input, output])- rtype:
None
setJointLimits
(indices, qmin, qmax, op[, ...])setCollisionFilter
(world, op)commandFilter
(indices, item, value)reset
()softStop
(indices)estop
(indices)setPosition
(indices, q)Backup: runs an immediate position command
moveToPosition
(indices, q, speed)Backup: runs a position command using a piecewise linear trajectory
setVelocity
(indices, v, ttl)Backup: runs a velocity command for ttl seconds using a piecewise linear trajectory.
setTorque
(indices, t, ttl)setPID
(indices, q, dq, t)setPIDGains
(indices, kP, kI, kD)getPIDGains
(indices)setPiecewiseLinear
(indices, ts, qs, relative)setPiecewiseCubic
(indices, ts, qs, vs, relative)isMoving
(indices)setToolCoordinates
(indices, xtool_local)getToolCoordinates
(indices)setGravityCompensation
(indices, gravity, ...)getGravityCompensation
(indices)setCartesianPosition
(indices, xparams, frame)moveToCartesianPosition
(indices, xparams, ...)moveToCartesianPositionLinear
(indices, ...)setCartesianVelocity
(indices, dxparams, ttl, ...)setCartesianForce
(indices, fparams, ttl, frame)cartesianPosition
(indices, q, frame)Emulates cartesianPosition.
cartesianVelocity
(indices, q, dq, frame)Emulates cartesianVelocity.
cartesianForce
(indices, q, t, frame)- CONTROL_MODES = ['setPID', 'setVelocity', 'setPosition', 'moveToPosition', 'setPiecewiseLinear', 'setPiecewiseCubic']
-
cartesianInterfaces:
Dict
[str
,_CartesianEmulatorData
]
-
stateFilters:
Dict
[Sequence
[int
],Dict
[str
,Callable
]]
-
commandFilters:
Dict
[Sequence
[int
],Dict
[str
,Callable
]]
-
virtualSensorMeasurements:
Dict
[str
,Tuple
[float
,Sequence
[float
]]]
- initialize(qsns, vsns, tsns, qcmd, vcmd, tcmd)[source]
Could be called before the emulator starts running to initialize the commanded joint positions before the emulator takes over.
- sendToInterface(interface, indices=None)[source]
Sends a command to the interface using the highest level interface as possible.
- Return type:
Tuple
[str
,str
]- Returns:
(desiredControlMode,baseControlMode) indicating which mode was desired and which was actually achieved.
- Return type:
tuple
- desiredControlMode(indices=None)[source]
Returns the highest level control mode requested of the joints. Returns None if no command is active.
if indices is not None, then it returns the desired control mode for the joints referred to by indices.
- getCommand(commandType, indices=None)[source]
Retrieves the args for the command to be sent to the actual interface on this time step.
if indices is not None, then it returns the command for the joints referred to by indices.
- onBaseCommand(desiredControlMode, sentControlMode, indices=None)[source]
To be called when the completer has decided which base control mode to use.
- promote(indices, controlType)[source]
To accept commands of the given controlMode, switches over the current state to the controlMode
- moveToPosition(indices, q, speed)[source]
Backup: runs a position command using a piecewise linear trajectory
- setVelocity(indices, v, ttl)[source]
Backup: runs a velocity command for ttl seconds using a piecewise linear trajectory. If ttl is not specified, uses ttl=1.
- cartesianPosition(indices, q, frame)[source]
Emulates cartesianPosition. Can also get link transforms.
- Parameters:
indices (str, int, or tuple) – if str or int, retrieves a link transform, and
frame
must be “world”. If a tuple, retrieves the position of the cartesian controller for the given indices, in the given frame.q (Vector) – the configuration of the full body
frame (str) – either “world”, “base”, “end effector”, or “tool”
- cartesianVelocity(indices, q, dq, frame)[source]
Emulates cartesianVelocity. Can also get link velocities.
- Parameters:
indices (str, int, or tuple) – if str or int, retrieves a link velocity, and
frame
must be “world”. If a tuple, retrieves the velocity of the cartesian controller for the given indices, in the given frame.q (Vector) – the configuration of the full body
dq (Vector) – the joint velocities of the full body
frame (str) – either “world”, “base”, “end effector”, or “tool”
- class klampt.control.robotinterfaceutils.RobotInterfaceLogger(interface, file)[source]
Bases:
object
A logger that will write parts of the RIL state to a CSV file.
TODO: make this a filter.
Attributes:
Methods:
step
()stop
()- TEST_PROPERTIES = ['controlRate', 'parts', 'sensors', 'enabledSensors', 'numJoints', 'indices']
- TEST_METHODS = ['clock', 'status', 'isMoving', 'sensedPosition', 'sensedVelocity', 'sensedTorque', 'commandedPosition', 'commandedVelocity', 'commandedTorque', 'destinationPosition', 'destinationVelocity', 'destinationTime']
- class klampt.control.robotinterfaceutils.RobotInterfaceRecorder(interface, file=typing.Union[typing.TextIO, str], playback=False, playback_delay=None)[source]
Bases:
object
Records / playbacks all RIL commands to disk.
Record usage:
interface = MyRobotInterface(...) recorder = RobotInterfaceRecorder(interface,'recording.txt') while True: ... issue commands recorder.step() #this does the work interface.endStep() ... sleep, visualize, etc recorder.stop()
Playback usage:
interface = MyRobotInterface(...) recorder = RobotInterfaceRecorder(interface,'recording.txt',playback=True) while not recorder.done(): recorder.step() #this does the work interface.endStep() ... sleep, visualize, etc
- Parameters:
interface (RobotInterfaceBase) – NOTE: must be stateful.
file (str or file-like) – the file to save to / load from
playback (bool) – whether to use record or playback mode
playback_delay (float, optional) – when in playback mode, how long to wait before the first command is issued. If None, uses the same timing as in the original recording (assumes clocks start at 0).
Methods:
step
()Call this after commands have been issued to
interface
but beforeinterface.endStep()
.stop
()- rtype:
None
done
()- rtype:
bool