klampt.control.simrobotinterface module

Used for testing code that works with the Klamp’t Robot Interface Layer on a simualted robot. Defines a variety of RobotInterfaceBase interfaces that work with Klamp’t simulations.

For each of the classes in this module, if you provide the simulator argument then this will automatically update your simulation upon each beginStep() / endStep() pair. Otherwise, you will have to step the simulation manually.

Classes:

SimPositionControlInterface(sim_controller)

Adapts a SimRobotController to the RobotInterfaceBase class in position control mode.

SimVelocityControlInterface(sim_controller)

Adapts a SimRobotController to the RobotInterfaceBase class in velocity control mode.

SimMoveToControlInterface(sim_controller[, ...])

Adapts a SimRobotController to the RobotInterfaceBase class in move-to control mode.

SimFullControlInterface(sim_controller[, ...])

Adapts a SimRobotController to the RobotInterfaceBase class, accepting position control, move to control, velocity control, and torque control modes.

KinematicSimControlInterface(robot[, robotInfo])

A very basic control interface that just sets the robot's config to the last setPosition command.

Functions:

make(robotModel)

Makes a default KinematicSimControlInterface for the robot.

class klampt.control.simrobotinterface.SimPositionControlInterface(sim_controller, simulator=None, robotInfo=None)[source]

Bases: _SimControlInterface

Adapts a SimRobotController to the RobotInterfaceBase class in position control mode.

Only implements setPosition, sensedPosition, and commandedPosition; you should use RobotInterfaceCompleter to fill in move-to control, cartesian control, velocity control, etc.

Methods:

setPosition(q)

Sets an instantaneous position command.

sensedPosition()

Retrieves the currently sensed joint position.

commandedPosition()

Retrieves the currently commanded joint position.

setPosition(q)[source]

Sets an instantaneous position command.

Parameters:

q (list of floats) – A list of floats giving the desired configuration of the robot.

sensedPosition()[source]

Retrieves the currently sensed joint position.

commandedPosition()[source]

Retrieves the currently commanded joint position.

class klampt.control.simrobotinterface.SimVelocityControlInterface(sim_controller, simulator=None, robotInfo=None)[source]

Bases: _SimControlInterface

Adapts a SimRobotController to the RobotInterfaceBase class in velocity control mode.

Only implements setVelocity, sensedPosition, and commandedPosition; you should use RobotInterfaceCompleter to fill in move-to control, cartesian control, position control, etc.

Methods:

setVelocity(v[, ttl])

Sets an instantaneous velocity command.

sensedPosition()

Retrieves the currently sensed joint position.

commandedPosition()

Retrieves the currently commanded joint position.

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.

sensedPosition()[source]

Retrieves the currently sensed joint position.

commandedPosition()[source]

Retrieves the currently commanded joint position.

class klampt.control.simrobotinterface.SimMoveToControlInterface(sim_controller, simulator=None, robotInfo=None)[source]

Bases: _SimControlInterface

Adapts a SimRobotController to the RobotInterfaceBase class in move-to control mode.

Only implements moveToPosition, sensedPosition, and commandedPosition; you should use RobotInterfaceCompleter to fill in position control, cartesian control, velocity control, etc.

Methods:

moveToPosition(q[, speed])

Sets a move-to position command.

sensedPosition()

Retrieves the currently sensed joint position.

commandedPosition()

Retrieves the currently commanded joint position.

isMoving([joint_idx])

Returns true if the robot / joint are currently moving

moveToPosition(q, speed=1.0)[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.

sensedPosition()[source]

Retrieves the currently sensed joint position.

commandedPosition()[source]

Retrieves the currently commanded joint position.

isMoving(joint_idx=None)[source]

Returns true if the robot / joint are currently moving

class klampt.control.simrobotinterface.SimFullControlInterface(sim_controller, simulator=None, robotInfo=None)[source]

Bases: _SimControlInterface

Adapts a SimRobotController to the RobotInterfaceBase class, accepting position control, move to control, velocity control, and torque control modes.

You should use RobotInterfaceCompleter to fill in move-to control, cartesian control, velocity control, etc.

Methods:

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, kD, kI)

Sets the PID gains.

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.

moveToPosition(q[, speed])

Sets a move-to position command.

isMoving([joint_idx])

Returns true if the robot / joint are currently moving

sensedPosition()

Retrieves the currently sensed joint position.

sensedVelocity()

Retrieves the currently sensed joint velocity.

sensedTorque()

Retrieves the currently sensed joint torque.

commandedVelocity()

Retrieves the currently commanded joint velocity.

commandedTorque()

Retrieves the currently commanded joint torque.

commandedPosition()

Retrieves the currently commanded joint position.

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, kD, kI)[source]

Sets the PID gains. Some controllers might not implement this even if they implement setPID…

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().

moveToPosition(q, speed=1.0)[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.

isMoving(joint_idx=None)[source]

Returns true if the robot / joint are currently moving

sensedPosition()[source]

Retrieves the currently sensed joint position.

sensedVelocity()[source]

Retrieves the currently sensed joint velocity.

sensedTorque()[source]

Retrieves the currently sensed joint torque.

commandedVelocity()[source]

Retrieves the currently commanded joint velocity.

commandedTorque()[source]

Retrieves the currently commanded joint torque.

commandedPosition()[source]

Retrieves the currently commanded joint position.

class klampt.control.simrobotinterface.KinematicSimControlInterface(robot, robotInfo=None)[source]

Bases: RobotInterfaceBase

A very basic control interface that just sets the robot’s config to the last setPosition command. Can also perform kinematic simulation of simulators.

Also performs joint limit testing and self collision checking. These change the status of the interface to non-‘ok’ error codes.

Methods:

klamptModel()

If applicable, returns the Klamp't RobotModel associated with this controller.

parts()

Returns a dictionary of (part-name,configuration index list) pairs defining the named parts of the robot.

controlRate()

Returns the control rate, in Hz

sensors()

Returns a list of names of possible sensors on this robot.

enabledSensors()

Returns a list of names of enabled sensors on this robot.

sensorMeasurements(name)

Returns the latest measurements from a sensor.

endStep()

This is called after the commands sent at each time step

status([joint_idx])

Returns a status string for the robot / given joint.

setPosition(q)

Sets an instantaneous position command.

reset()

If the robot has a non-normal status code, attempt to reset it to normal operation.

sensedPosition()

Retrieves the currently sensed joint position.

commandedPosition()

Retrieves the currently commanded joint position.

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.

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.

controlRate()[source]

Returns the control rate, in Hz

sensors()[source]

Returns a list of names of possible sensors on this robot.

enabledSensors()[source]

Returns a list of names of enabled sensors on this robot.

sensorMeasurements(name)[source]

Returns the latest measurements from a sensor. Interpretation of the result is sensor-dependent.

endStep()[source]

This is called after the commands sent at each time step

status(joint_idx=None)[source]

Returns a status string for the robot / given joint. ‘ok’ means everything is OK.

setPosition(q)[source]

Sets an instantaneous position command.

Parameters:

q (list of floats) – A list of floats giving the desired configuration of the robot.

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’

sensedPosition()[source]

Retrieves the currently sensed joint position.

commandedPosition()[source]

Retrieves the currently commanded joint position.

klampt.control.simrobotinterface.make(robotModel)[source]

Makes a default KinematicSimControlInterface for the robot. This module can be referenced using ‘klampt.control.simrobotinterface’, e.g. as an argument to the klampt_control app.