nicomotion

The nicomotion package contains classes to control the movement of the NICO robot.

Kinematics

The Kinematics class allows inverse kinematics control of the NICO motors.

Motion

The Motion class allows direct control over the NICO motors.

class nicomotion.Motion.Motion(motorConfig='config.json', vrep=False, vrepConfig=None, ignoreMissing=False, monitorHandCurrents=True)

Bases: object

The Motion class provides a high level interface to various movement related functions of the NICO robot

_adjust_port_latency()

Lowers the latency of the NICO port to prevent communication delays

callVREPRemoteApi(func_name, *args, **kwargs)

Calls any remote API func in a thread_safe way.

Parameters
  • func_name (str) – name of the remote API func to call

  • args – args to pass to the remote API call

  • kwargs – args to pass to the remote API call

Returns

api response

Note

You can add an extra keyword to specify if you want to use the streaming or sending mode. The oneshot_wait mode is used by default (see here for details about possible modes).

Warning

You should not pass the clientId and the operationMode as arguments. They will be automatically added.

changeAngle(jointName, change, fractionMaxSpeed)

Changes the angle of a given joint by an angle (in degree)

Parameters
  • jointName (str) – Name of the joint

  • angle (float) – Angle (in degree)

  • fractionMaxSpeed (float) – Movement speed of joint

cleanup()

Cleans up the current connection to the robot. After this you can no longer control the robot

closeHand(handName, fractionMaxSpeed=1.0, percentage=1.0)

Closes the specified hand. handName can be ‘RHand’ or ‘LHand’

Parameters
  • handName (str) – Name of the hand (RHand, LHand)

  • fractionMaxSpeed (float) – Speed at which hand should close. Default: 1.0

  • percentage (float) – Percentage hand should open. 0.0 < percentage <= 1.0

disableForceControl(jointName)

Disables force control for a single joint

Parameters

jointName (str) – Name of the joint

disableForceControlAll()

Disables force control for all joints which support this feature

disableTorque(jointName)

Disables torque on a single joint.

Parameters

jointName (str) – Name of the motor

disableTorqueAll()

Disables toruqe on all joints

enableForceControl(jointName, goalForce)

Enables force control for a single joint

Parameters
  • jointName (str) – Name of the joint

  • goalForce (int) – Goal force (0-2000)

enableForceControlAll(goalForce=500)

Enables force control for all joints which support this feature

Parameters

goalForce (int) – Goal force (0-2000)

enableTorque(jointName)

Enables torque on a single joint.

Parameters

jointName (str) – Name of the motor

enableTorqueAll()

Enables toruqe on all joints

getAngle(jointName)

Returns the current angle of a given joint (in degree)

Parameters

jointName (str) – Name of the joint

Returns

Angle of the joint (degree)

Return type

float

getAngleLowerLimit(jointName)

Returns the lower angle limit of a joint (in degree)

Parameters

jointName (str) – Name of the joint

Returns

Lower angle limit of the joint (degree)

Return type

float

getAngleUpperLimit(jointName)

Returns the upper angle limit of a joint (in degree)

Parameters

jointName (str) – Name of the joint

Returns

Upper angle limit of the joint (degree)

Return type

float

getConfig()

Returns the JSON configuration of motors

Returns

motor configuration

Return type

dict

getCurrent(jointName)

Returns the current current of a motor

Parameters

jointName (str) – Name of the joint

Returns

Current of the joint

Return type

float

getJointNames()

Returns all joint names

Returns

List with joint names

Return type

list

getPID(jointName)

Returns the current stifftness of a motor. For more information see http://support.robotis.com/en/product/actuator/dynamixel/mx_series/mx-64at_ar.htm#Actuator_Address_1A

Parameters

jointName (str) – Name of the joint

Returns

Tupel: p,i,d

Return type

tuple

getPalmSensorReading(handName)

Returns current reading of the palm IR sensor of the specified hand.

Parameters

handName (str) – Name of the hand (RHand, LHand)

Returns

Raw IR sensor value

Return type

int

getPose(objectName, relativeToObject=None)

Returns the current pose of the scene object with given name relative to the second given object

Parameters
  • objectName (str) – Name of the object

  • relativeToObject (str) – Name of the object that the position should be relative to

Returns

Position of the requestet object in x,y,z coordinates relative to the second object

Return type

list of three floats

getSensorNames()

Returns all sensor names

Returns

List with sensor names

Return type

list

getSimulationDeltatime()

Gets the timeframe which one simulation step represents.

Returns

timeframe of one simulation step in seconds

Return type

float

getSpeed(jointName)

Returns the current speed of a motor

Parameters

jointName (str) – Name of the joint

Returns

Speed of the joint

Return type

float

getStiffness(jointName)

Returns the current stiffness of a motor

Parameters

jointName (str) – Name of the joint

Returns

Stiffness of the joint

Return type

float

getTemperature(jointName)

Returns the current temperature of a motor

Parameters

jointName (str) – Name of the joint

Returns

Temperature of the joint

Return type

float

getTorqueLimit(jointName)

Returns the torque limit of a joint

Parameters

jointName (str) – Name of the joint

Returns

Torque limit of the joint

Return type

float

getVrep()

Returns if vrep simulation is used or not

Returns

is vrep or real NICO used

Return type

boolean

getVrepIO()

Gives access to pypots vrep IO (see https://poppy-project.github.io/pypot/pypot.vrep.html#pypot.vrep.io.VrepIO)

Returns

Pypot vrep IO

Return type

pypot.vrep.io

nextSimulationStep()

Advances the V-REP simulation by one step if synchronize was set on startSimulation().

openHand(handName, fractionMaxSpeed=1.0, percentage=1.0)

Opens the specified hand. handName can be ‘RHand’ or ‘LHand’

Parameters
  • handName (str) – Name of the hand (RHand, LHand)

  • fractionMaxSpeed (float) – Speed at which hand should open. Default: 1.0

  • percentage (float) – Percentage hand should open. 0.0 < percentage <= 1.0

static pyrepConfig()

Returns a default config dict

Returns

dict

resetSimulation()

Restarts the V-REP simulation

setAngle(jointName, angle, fractionMaxSpeed)

Sets the angle of a given joint to an angle (in degree)

Parameters
  • jointName (str) – Name of the joint

  • angle (float) – Angle (in degree)

  • fractionMaxSpeed (float) – Movement speed of joint

setAngleLowerLimit(jointName, angle)

Sets the lower angle limit of a joint (in degree)

Parameters
  • jointName (str) – Name of the joint

  • angle (float) – Angle (in degree)

setAngleUpperLimit(jointName, angle)

Sets the upper angle limit of a joint (in degree)

Parameters
  • jointName (str) – Name of the joint

  • angle (float) – Angle (in degree)

setHandPose(handName, poseName, fractionMaxSpeed=1.0, percentage=1)

Executes pose with the specified hand. Most poses only works with the RH5D and RH7D 4-finger hands. Make sure to open the hand beforehand.

Known poses are: (“thumbsUp”, “pointAt”, “okSign”, “pinchToIndex”, “keyGrip”, “pencilGrip”, “closeHand”, “openHand”).

handName can be ‘RHand’ or ‘LHand’

Parameters
  • handName (str) – Name of the hand (RHand, LHand)

  • poseName (str) – Name of the pose (“thumbsUp”, “pointAt”, “okSign”, “pinchToIndex”, “keyGrip”, “pencilGrip”, “closeHand”, “openHand”)

  • fractionMaxSpeed (float) – Speed at which hand move. Default: 1.0

  • percentage (float) – Percentage of the pose to execute. 0.0 < percentage <= 1.0 (default)

setMaximumSpeed(maximumSpeed)

Sets the maximum allowed speed (in fraction of maximum possible speed). When giving a higher speed to any other functions the movement won’t go over the value set here

Parameters

maximumSpeed – Maximum allowed speed (0 <= maximumSpeed <= 1.0)

setPID(jointName, p, i, d)

Sets the PID controller for a single motor. For more information see http://support.robotis.com/en/product/actuator/dynamixel/mx_series/mx-64at_ar.htm#Actuator_Address_1A

Parameters
  • jointName (str) – Name of the joint

  • p (float) – Proportional band

  • i (float) – Integral action

  • d (float) – Derivative action

setSimulationDeltatime(dt)

Sets the timeframe which one simulation step represents.

Only works while the simulation is stopped and dt is set to custom.

Parameters

dt (float) – timeframe of one simulation step in seconds

setStiffness(jointName, stiffness)

Sets the stiffness (0 <= stiffness <= 1) for a single motor

Parameters
  • jointName (str) – Name of the joint

  • stiffness (float) – Target stiffness

startSimulation(synchronize=False)

Starts the V-REP Simulation. If ‘synchronize’ is set True the simulation steps will not advance until nextSimulationStep() is called. (NOTE: pyrep is always in synchronous mode)

Parameters

synchronize (bool) – Enables control over simulation time steps

stopSimulation()

Stops the V-REP simulation

toSafePosition()

Moves the robot to its initial state of this session. In this state it should be safe to disable the force control. To receive a collision free motion trajectories use the corresponding moveitWrapper function instead.

static vrepRemoteConfig()

Returns a default config dict

Returns

dict

Mover

The Mover class allows playback of prerecorded positions of the NICO motors.

class nicomotion.Mover.Mover(robot, stiff_off=False, path_to_config_file='mover.conf')

Bases: object

calc_move_file(fname, target_fname, number)
freeze_joints(subsetfname=None, stiffness=None, unfreeze=False)
move_file_position(fname, subsetfname=None, move_speed=0.04)
move_position(target_positions, speed, real=True)
play_movement(fname, subsetfname=None, move_speed=0.04)
record_movement(fname=None)
record_position(fname=None)