Overview

ALMotion provides methods that help make Nao move. It contains commands for manipulating joint angles, joint stiffness, and a higher level API for controling walks.

Methods

void angleInterpolation (const AL::ALValue& names, const AL::ALValue& angleLists, const AL::ALValue& timeLists, const bool& isAbsolute)

Interpolates one or multiple joints to a target angle or along timed trajectories. This is a blocking call.

names

Name or names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

angleLists

An angle, list of angles or list of list of angles in radians

timeLists

A time, list of times or list of list of times in seconds

isAbsolute

If true, the movement is described in absolute angles, else the angles are relative to the current angle.

Example in python :

# Example showing a single target angle for one joint 
# Interpolate the head yaw to 1.0 radian in 1.0 second 
names      = "HeadYaw" 
angleLists = 1.0 
timeLists  = 1.0 
isAbsolute = True 
proxy.angleInterpolation(names, angleLists, timeLists, isAbsolute) 

Example in c++ :

// Example showing a single target angle for one joint 
// Interpolate the head yaw to 1.0 radian in 1.0 second 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy();
AL::ALValue names      = "HeadYaw"; 
AL::ALValue angleLists = 1.0f; 
AL::ALValue timeLists  = 1.0f; 
bool isAbsolute        = true; 
motion->angleInterpolation(names, angleLists, timeLists, isAbsolute); 

Example in python :

# Example showing a single trajectory for one joint
# Interpolate the head yaw to 1.0 radian and back to zero in 2.0 seconds
names      = "HeadYaw" 
#              2 angles 
angleLists = [1.0, 0.0] 
#              2 times 
timeLists  = [1.0, 2.0] 
isAbsolute = True 
proxy.angleInterpolation(names, angleLists, timeLists, isAbsolute) 

Example in c++ :

// Example showing a single trajectory for one joint
// Interpolate the head yaw to 1.0 radian and back to zero in 2.0 seconds 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy();  
AL::ALValue names      = "HeadYaw"; 
AL::ALValue angleLists = AL::ALValue::array(1.0f, 0.0f); 
AL::ALValue timeLists  = AL::ALValue::array(1.0f, 2.0f); 
bool isAbsolute        = true; 
motion->angleInterpolation(names, angleLists, timeLists, isAbsolute); 

Example in python :

# Example showing multiple trajectories
# Interpolate the head yaw to 1.0 radian and back to zero in 2.0 seconds
# while interpolating HeadPitch up and down over a longer period.
names  = ["HeadYaw","HeadPitch"]
# Each joint can have lists of different lengths, but the number of 
# angles and the number of times must be the same for each joint.
# Here, the second joint ("HeadPitch") has three angles, and 
# three corresponding times.
angleLists  = [[1.0, 0.0], [-0.5, 0.5, 0.0]]
timeLists   = [[1.0, 2.0], [ 1.0, 2.0, 3.0]]
isAbsolute  = True
proxy.angleInterpolation(names, angleLists, timeLists, isAbsolute)

Example in c++ :

// Example showing multiple trajectories
// Interpolate the HeadYaw to 1.0 radian and back to zero in 2.0 seconds
// while interpolating HeadPitch up and down over a longer period.
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
AL::ALValue names = AL::ALValue::array("HeadYaw", "HeadPitch"); 
// Each joint can have lists of different lengths, but the number of 
// angles and the number of times must be the same for each joint.
// Here, the second joint ("HeadPitch") has three angles, and 
// three corresponding times.
AL::ALValue angleLists; 
angleLists.arraySetSize(2); 
angleLists[0] = AL::ALValue::array(1.0f, 0.0f); 
angleLists[1] = AL::ALValue::array(-0.5f, 0.5f, 0.0f); 
 
AL::ALValue timeLists; 
timeLists.arraySetSize(2); 
timeLists[0] = AL::ALValue::array(1.0f, 2.0f); 
timeLists[1] = AL::ALValue::array(1.0f, 2.0f, 3.0f); 
 
bool isAbsolute = true; 
 
motion->angleInterpolation(names, angleLists, timeLists, isAbsolute); 

void angleInterpolationBezier (const vector<string>& jointNames, const AL::ALValue& times, const AL::ALValue& controlPoints)

Interpolates a sequence of timed angles for several motors using bezier control points. This is a blocking call.

jointNames

A vector of joint names

times

An ragged ALValue matrix of floats. Each line corresponding to a motor, and column element to a control point.

controlPoints

An ALValue array of arrays each containing [float angle, Handle1, Handle2], where Handle is [int InterpolationType, float dAngle, float dTime] descibing the handle offsets relative to the angle and time of the point. The first bezier param describes the handle that controls the curve preceeding the point, the second describes the curve following the point.

void angleInterpolationWithSpeed (const AL::ALValue& names, const AL::ALValue& targetAngles, const float& maxSpeedFraction)

Interpolates one or multiple joints to a target angle, using a fraction of max speed. Only one target angle is allowed for each joint. This is a blocking call.

names

Name or names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

targetAngles

An angle, or list of angles in radians

maxSpeedFraction

A fraction.

Example in python :

# Example showing a single target for one joint
names             = "HeadYaw" 
targetAngles      = 1.0 
maxSpeedFraction  = 0.2 # Using 20% of maximum joint speed 
proxy.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction)

Example in c++ :

// Example showing a single target for one joint
AL::ALValue names        = "HeadYaw"; 
AL::ALValue targetAngles = 1.0f;
float maxSpeedFraction   = 0.2f; // Using 20% of maximum joint speed 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction); 

Example in python :

# Example showing multiple joints
# Instead of listing each joint, you can use a chain name, which will 
# be expanded to contain all the joints in the chain. In this case,
# "Head" will be interpreted as ["HeadYaw", "HeadPitch"]
names  = "Head"
# We still need to specify the correct number of target angles
targetAngles     = [0.5, 0.25]
maxSpeedFraction = 0.2 # Using 20% of maximum joint speed 
proxy.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction)

Example in c++ :

// Example showing multiple joints 
// Instead of listing each joint, you can use a chain name, which will 
// be expanded to contain all the joints in the chain. In this case,
// "Head" will be interpreted as ["HeadYaw", "HeadPitch"]
AL::ALValue names  = "Head"; 
// We still need to specify the correct number of target angles 
AL::ALValue targetAngles = AL::ALValue::array(0.5f, 0.25f); 
float maxSpeedFraction  = 0.2f; // Using 20% of maximum joint speed 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction); 

Example in python :

# Example showing body zero position
# Instead of listing each joint, you can use a the name "Body" 
names  = "Body"
# We still need to specify the correct number of target angles, so 
# we need to find the number of joints that this Nao has.
# Here we are using the getJointNames method, which tells us all
# the names of the joints in the alias "Body".
# We could have used this list for the "names" parameter.
numJoints = len(proxy.getJointNames("Body"))
# Make a list of the correct length. All angles are zero.
targetAngles  = [0.0]*numJoints
# Using 10% of maximum joint speed
maxSpeedFraction  = 0.1
proxy.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction)

void changeAngles (const AL::ALValue& names, const AL::ALValue& changes, const float& fractionMaxSpeed)

Changes Angles. This is a non-blocking call.

names

The name or names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

changes

One or more changes in radians

fractionMaxSpeed

The fraction of maximum speed to use

Example in python :

# Example showing a slow, relative move of "HeadYaw".
# Calling this multiple times will move the head further.
names            = "HeadYaw"
changes          = 0.25
fractionMaxSpeed = 0.05
proxy.changeAngles(names, changes, fractionMaxSpeed) 

Example in c++ :

// Example showing a slow, relative move of "HeadYaw".
// Calling this multiple times will move the head further.
AL::ALValue names      = "HeadYaw"; 
AL::ALValue changes    = 0.25f; 
float fractionMaxSpeed = 0.05f; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->changeAngles(names, changes, fractionMaxSpeed); 

void changePosition (const string& effectorName, const int& space, const vector<float>& positionChange, const float& fractionMaxSpeed, const int& axisMask)

Creates a move of an end effector in cartesian space. This is a non-blocking call.

effectorName

Name of the effector.

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

positionChange

6D position change array (xd, yd, zd, wxd, wyd, wzd) in meters and radians

fractionMaxSpeed

The fraction of maximum speed to use

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

Example in python :

# Example showing how to move forward (2cm) "LArm". 
effectorName     = "LArm" 
space            = 2 # SPACE_NAO 
positionChange   = [0.02, 0.0, 0.0, 0.0, 0.0, 0.0] 
fractionMaxSpeed = 0.5 
axisMask         = 7 
proxy.changePosition(effectorName, space, positionChange, fractionMaxSpeed, axisMask)

Example in c++ :

// Example showing how to move forward (2cm) "LArm". 
std::string effectorName  = "LArm"; 
int space                 = 2; // SPACE_NAO 
std::vector<float> positionChange(6, 0.0f); 
positionChange[0] = 0.02f; 
float fractionMaxSpeed    = 0.5f; 
int axisMask              = 7; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->changePosition(effectorName, space, positionChange, fractionMaxSpeed, axisMask); 

void changeTransform (const string& chainName, const int& space, const vector<float>& transform, const float& fractionMaxSpeed, const int& axisMask)

Moves an end-effector to the given position and orientation transform. This is a non-blocking call.

chainName

Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso"

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

transform

ALTransform arrays

fractionMaxSpeed

The fraction of maximum speed to use

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

Example in python :

# Example showing how to set Torso Transform, using a fraction of max speed
chainName        = "Torso" 
space            = 2 # SPACE_NAO 
transform        = [1.0, 0.0, 0.0, 0.05, 
                    0.0, 1.0, 0.0, 0.00, 
                    0.0, 0.0, 1.0, 0.00] # Absolute Position
fractionMaxSpeed = 0.2 
axisMask         = 63 
proxy.changeTransform(chainName, space, transform, fractionMaxSpeed, axisMask)

Example in c++ :

// Example showing how to set Torso Transform, using a fraction of max speed 
std::string chainName  = "Torso"; 
int space     = 2; // SPACE_NAO 
std::vector<float> transform(12, 0.0f); 
transform[0]  = 1.0f;  // 1.0f, 0.0f, 0.0f, 0.05f 
transform[3]  = 0.05f; // 0.0f, 1.0f, 0.0f, 0.0f 
transform[5]  = 1.0f;  // 0.0f, 0.0f, 1.0f, 0.0f 
transform[10] = 1.0f; 
float fractionMaxSpeed = 0.2f; 
int axisMask  = 63; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->changeTransform(chainName, space, transform, fractionMaxSpeed, axisMask); 

void openHand (const string& handName)

Opens the hand, then cuts motor current to conserve energy. This is a blocking call.

handName

The name of the hand. Could be: "RHand or "LHand"

Example in python :

# Example showing how to open the left hand
proxy.openHand('LHand')

Example in c++ :

// Example showing how to open the right hand. 
std::string handName = "RHand"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->openHand(handName); 

void closeHand (const string& handName)

Closes the hand, then cuts motor current to conserve energy. This is a blocking call.

handName

The name of the hand. Could be: "RHand" or "LHand"

Example in python :

# Example showing how to close the right hand.
handName  = 'RHand'
proxy.closeHand(handName)

Example in c++ :

// Example showing how to close the right hand. 
std::string handName = "RHand"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->closeHand(handName); 

vector<float> getAngles (const AL::ALValue& names, const bool& useSensors)

Gets the angles of the joints

names

Names the joints, chains, "Body", "BodyJoints" or "BodyActuators".

useSensors

If true, sensor angles will be returned

Returns

Joint angles in radians.

Example in python :

# Example that finds the difference between the command and sensed angles. 
names  = "Body" 
useSensors  = False 
commandAngles = proxy.getAngles(names, useSensors) 
useSensors  = True 
sensorAngles = proxy.getAngles(names, useSensors) 
errors = [] 
for i in range(0, len(commandAngles)): 
  errors.append(commandAngles[i]-sensorAngles[i]) 
print "Errors", errors 

Example in c++ :

// Example that finds the difference between the command and sensed angles. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::string names = "Body"; 
bool useSensors   = false; 
std::vector<float> commandAngles = motion->getAngles(names, useSensors); 
useSensors = true; 
std::vector<float> sensorAngles = motion->getAngles(names, useSensors); 

vector<string> getJointNames (const string& name)

Gets the names of all the joints in the collection.

name

Name of a chain, "Body", "BodyJoints" or "BodyActuators".

Returns

Vector of strings, one for each joint in the collection

Example in python :

# Example showing how to get the names of all the joints in the body. 
bodyNames = proxy.getJointNames("Body") 

Example in c++ :

// Example showing how to get the names of all the joints in the body. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<std::string> bodyNames = motion->getJointNames("Body"); 

Example in python :

# Example showing how to get the names of all the joints in the left leg. 
leftLegJointNames = proxy.getJointNames("LLeg") 

Example in c++ :

// Example showing how to get the names of all the joints in the left leg. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<std::string> leftLegJointNames = motion->getJointNames("LLeg"); 

AL::ALValue getLimits (const string& name)

Get the minAngle, maxAngle, and maxChangePerCycle for a given chain in the body.

name

Name of a joint, chain, "Body", "BodyJoints" or "BodyActuators".

Returns

Array of ALValue arrays containing the minAngle, maxAngle and maxChangePerCycle for all the joints specified.

Example in python :

# Example showing how to get the limits for the whole body 
name = "Body" 
limits = proxy.getLimits(name) 
jointNames = proxy.getJointNames(name) 
for i in range(0,len(limits)): 
  print jointNames[i], "MinAngle", limits[i][0] 
  print "MaxAngle", limits[i][1],"MaxChange", limits[i][2] 

vector<float> getPosition (const string& name, const int& space, const bool& useSensorValues)

Gets a Position relative to the TASK_SPACE.

name

Name of the item. Could be: Head, LArm, RArm, LLeg, RLeg, Torso, CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4.

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

useSensorValues

If true, the sensor values will be used to determine the position.

Returns

Vector containing the Position6D using meters and radians (x, y, z, wx, wy, wz)

Example in python :

# Example showing how to get the position of the top camera 
name  = "CameraTop" 
space  = 1 
useSensorValues  = True 
result = proxy.getPosition(name, space, useSensorValues) 
print "Position of", name, " in World is :", result 

Example in c++ :

// Example showing how to get the position of the top camera 
std::string name = "CameraTop"; 
int space = 1; 
bool useSensorValues = true; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> result = motion->getPosition(name, space, useSensorValues); 
 std::cout << "Position (x, y, z): " << result.at(0) << ", " << result.at(1) << ", " << result.at(2) << std::endl; 
 std::cout << "Rotation (x, y, z): " << result.at(3) << ", " << result.at(4) << ", " << result.at(5) << std::endl; 

vector<float> getRobotPosition (const bool& useSensors)

Gets the World Absolute Robot Position.

useSensors

If true, use the sensor values

Returns

A vector containing the World Absolute Robot Position. (Absolute Position X, Absolute Position Y, Absolute Angle Z)

Example in python :

# Example showing how to get a simplified robot position in world. 
useSensorValues = False 
result = proxy.getRobotPosition(useSensorValues) 
print "Robot Position", result 

Example in c++ :

// Example showing how to get a simplified robot position in world. 
bool useSensorValues = false; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> result = motion->getRobotPosition(useSensorValues); 

vector<float> getRobotVelocity ()

Gets the World Absolute Robot Velocity.

Returns

A vector containing the World Absolute Robot Velocity. (Absolute Velocity Translation X, Absolute Velocity Translation Y, Absolute Velocity Rotation WZ)

Example in python :

# Example showing how to get a simplified robot velocity in world. 
result = proxy.getRobotVelocity() 
print "Robot Velocity", result 

Example in c++ :

// Example showing how to get a simplified robot velocity in world. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> result = motion->getRobotVelocity(); 

vector<float> getStiffnesses (const AL::ALValue& jointName)

Gets stiffness of a joint or group of joints

jointName

Name of the joints, chains, "Body", "BodyJoints" or "BodyActuators".

Returns

One or more stiffnesses. 1.0 indicates maximum stiffness. 0.0 indicated minimum stiffness

Example in python :

# Example showing how to get the Body stiffnesses 
jointName  = "Body" 
stiffnesses = proxy.getStiffnesses(jointName) 
print "Body Stiffnesses", stiffnesses 

Example in c++ :

// Example showing how to get the Body stiffnesses 
std::string jointName = "Body"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> stiffnesses = motion->getStiffnesses(jointName); 

string getSummary ()

Returns a string representation of the Model's state

Returns

A formated string

Example in python :

# Example showing how to get a summary of Nao's state
print proxy.getSummary()

vector<float> getTransform (const string& name, const int& space, const bool& useSensorValues)

Gets an Homogenous Transform relative to the TASK_SPACE.

name

Name of the item. Could be: any joint or chain or sensor (Head, LArm, RArm, LLeg, RLeg, Torso, HeadYaw, ..., CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4.

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

useSensorValues

If true, the sensor values will be used to determine the position.

Returns

Vector of 16 floats corresponding to the values of the matrix, line by line.

Example in python :

# Example showing how to get the end of the right arm as a transform 
# represented in torso space. The result is a 4 by 4 matrix composed 
# of a 3*3 rotation matrix and a column vector of positions. 
name  = 'RArm' 
space  = 0 
useSensorValues  = True 
result = proxy.getTransform(name, space, useSensorValues) 
for i in range(0,4): 
  for j in range(0,4): 
    print result[4*i + j], 
  print '' 

Example in c++ :

// Example showing how to get the end of the right arm as a transform 
// represented in torso space. 
std::string name  = "RArm"; 
int space  = 0; // TORSO_SPACE 
bool useSensorValues  = false; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> result = motion->getTransform(name, space, useSensorValues); 
// R R R x 
// R R R y 
// R R R z 
// 0 0 0 1 
std::cout << result.at(0) << " " << result.at(1) << " " << result.at(2) << " " << result.at(3) << std::endl; 
std::cout << result.at(4) << " " << result.at(5) << " " << result.at(6) << " " << result.at(7) << std::endl; 
std::cout << result.at(8) << " " << result.at(9) << " " << result.at(10) << " " << result.at(11) << std::endl; 

float getMass (const string& pName)

Gets the mass of a joint, chain, "Body" or "BodyJoints".

pName

Name of the body which we want the mass. "Body", "BodyJoints" and "Com" give the total mass of nao. For the chain, it gives the total mass of the chain.

Returns

The mass in kg.

Example in python :

# Example showing how to get the mass of "HeadYaw". 
pName = "HeadYaw" 
mass = proxy.getMass(pName) 

Example in c++ :

// Example showing how to get the mass of "HeadYaw". 
std::string pName = "HeadYaw"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
float mass = motion->getMass(pName); 

Example in python :

# Example showing how to get the mass "LLeg" chain. 
pName = "LLeg" 
print "LLeg : ", proxy.getMass(pName) 
 
# It is equivalent to the following script 
pNameList = ["LHipYawPitch", "LHipRoll", "LHipPitch", "LKneePitch", "LAnkleRoll", "LAnklePitch"] 
mass = 0 
for pName in pNameList: 
    mass = mass + proxy.getMass(pName) 
print "LLeg :", mass 

vector<float> getCOM (const string& pName, const int& pSpace, const bool& pUseSensorValues)

Gets the COM of a joint, chain, "Body" or "BodyJoints".

pName

Name of the body which we want the mass. In chain name case, this function give the com of the chain.

pSpace

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

pUseSensorValues

If true, the sensor values will be used to determine the position.

Returns

The COM position (meter).

Example in python :

# Example showing how to get the COM position of "HeadYaw". 
pName = "HeadYaw" 
pSpace = 0 # SPACE_TORSO 
pUseSensors = False 
pos = proxy.getCOM(pName, pSpace, pUseSensors) 
print "HeadYaw COM Position: x = ", pos[0], " y:", pos[1], " z:", pos[2] 

Example in c++ :

// Example showing how to get the COM of "HeadYaw". 
std::string pName = "HeadYaw"; 
int pSpace = 0; // SPACE_TORSO 
bool pUseSensors = false; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
std::vector<float> pos = motion->getCOM(pName, pSpace, pUseSensors); 

AL::ALValue getRobotConfig ()

Get the robot configuration.

Returns

ALValue arrays containing the robot parameter names and the robot parameter values.

Example in python :

# Example showing how to get the robot config 
robotConfig = proxy.getRobotConfig() 
for i in range(len(robotConfig[0])): 
    print robotConfig[0][i], ": ", robotConfig[1][i] 
 
# "Model Type"   : "naoAcademics", "naoRobocup", "naoT14" or "naoT2". 
# "Head Version" : "V3.2" or "V3.3". 
# "Body Version" : "V3.2" or "V3.3". 
# "Laser"        : True or False. 
# "Legs"         : True or False. 
# "Arms"         : True or False. 
# "Extended Arms": True or False. 
# "Hands"        : True or False. 

void killAll ()

Kills all tasks.

Example in python :

# Example showing how to kill all the tasks.
proxy.killAll()

Example in c++ :

// Example showing how to kill all the tasks. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->killAll(); 

bool killTask (const int& motionTaskID)

Kills a motion task.

motionTaskID

TaskID of the motion task you want to kill.

Returns

Return true if the specified motionTaskId has been killed.

Example in python :

# This function not work with broker ID !!
# use prox.stop() with broker ID

# This function is useful to kill motion Task
# To see the current motionTask please use getTaskList() function

proxy.post.angleInterpolation('HeadYaw', 90*motion.TO_RAD, 10, True)
time.sleep(3)
TaskList = proxy.getTaskList()
uiMotion = TaskList[0][1]
proxy.killTask(uiMotion)

void positionInterpolation (const string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& durations, const bool& isAbsolute)

Moves an end-effector to the given position and orientation over time. This is a blocking call.

chainName

Name of the chain. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso"

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

path

Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

durations

Vector of times in seconds corresponding to the path points

isAbsolute

If true, the movement is absolute else relative

Example in python :

# Example of a cartesian foot trajectory 
# Warning: Needs a PoseInit before executing 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianFoot.py 
import motion 
 
space      =  motion.SPACE_NAO 
axisMask   = 63                     # control all the effector's axes
isAbsolute = False
 
# Lower the Torso and move to the side 
effector   = "Torso" 
path       = [0.0, -0.07, -0.03, 0.0, 0.0, 0.0] 
time       = 2.0                    # seconds 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, time, isAbsolute) 
 
# LLeg motion 
effector   = "LLeg" 
path       = [0.0,  0.06,  0.00, 0.0, 0.0, 0.8] 
times      = 2.0            # seconds 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 

Example in c++ :

// Example of a cartesian foot trajectory 
// Warning: Needs a PoseInit before executing 
int space       =  2; // SPACE_NAO 
int axisMask    = 63; // control all the effector's axes 
bool isAbsolute = false; 
 
// Lower the Torso and move to the side 
std::string effector = "Torso"; 
AL::ALValue path = AL::ALValue::array(0.0f, -0.07f, -0.03f, 0.0f, 0.0f, 0.0f); 
AL::ALValue time = 2.0f; // seconds 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->positionInterpolation(effector, space, path, 
                            axisMask, time, isAbsolute); 
 
// LLeg motion 
effector   = "LLeg"; 
path       = AL::ALValue::array(0.0f,  0.06f,  0.00f, 0.0f, 0.0f, 0.8f); 
time       = 2.0f; // seconds 
motion->positionInterpolation(effector, space, path, 
                            axisMask, time, isAbsolute); 

Example in python :

# Example showing a path of five positions 
# Warning: Needs a PoseInit before execution 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianTorso.py 
import motion 
 
effector   = "Torso" 
space      =  motion.SPACE_NAO 
 
# Position Only 
axisMask   = 63                             # Full control 
isAbsolute = False 
 
# define the changes relative to the current position 
dx         = 0.050                          # translation axis X (meter) 
dy         = 0.055                          # translation axis Y (meter) 
 
path       = [ 
  [+dx, 0.0, 0.0, 0.0, 0.0, 0.0],           # Point 1 
  [0.0, -dy, 0.0, 0.0, 0.0, 0.0],           # Point 2 
  [-dx, 0.0, 0.0, 0.0, 0.0, 0.0],           # Point 3 
  [0.0, +dy, 0.0, 0.0, 0.0, 0.0],           # Point 4 
  [+dx, 0.0, 0.0, 0.0, 0.0, 0.0],           # Point 5 
  [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]]           # Point 6 
 
times      = [1.0, 2.0, 3.0, 4.0, 5.0, 6.0] # seconds 
 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 

Example in python :

# Simultaneously control three effectors : 
# the Torso, the Left Arm and the Right Arm 
# Warning: Needs a PoseInit before executing 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianTorsoArm1.py 
import motion 
 
space      = motion.SPACE_NAO 
coef       = 0.5                   # motion speed 
times      = [coef, 2.0*coef, 3.0*coef, 4.0*coef] 
isAbsolute = False 
 
# Relative movement between current and desired positions 
dy         = +0.06                 # translation axis Y (meters) 
dz         = -0.03                 # translation axis Z (meters) 
dwx        = +0.30                 # rotation axis X (radians) 
 
# Motion of Torso with post process 
effector   = "Torso" 
path       = [ 
  [0.0, -dy,  dz, -dwx, 0.0, 0.0], # Point 1 
  [0.0, 0.0, 0.0,  0.0, 0.0, 0.0], # Point 2 
  [0.0, +dy,  dz, +dwx, 0.0, 0.0], # Point 3 
  [0.0, 0.0, 0.0,  0.0, 0.0, 0.0]] # Point 4 
axisMask   = 63                    # control all the effector axes 
proxy.post.positionInterpolation(effector, space, path, 
                                 axisMask, times, isAbsolute) 
 
# Motion of Arms with block process 
axisMask   = 7                     # control just the position 
times      = [1.0*coef, 2.0*coef]  # seconds 
 
# Motion of Right Arm during the first half of the Torso motion 
effector   = "RArm" 
path       = [ 
  [0.0, -dy, 0.0, 0.0, 0.0, 0.0],  # Point 1 
  [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]]  # Point 2 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 
 
# Motion of Left Arm during the last half of the Torso motion 
effector   = "LArm" 
path       = [ 
  [0.0,  dy, 0.0, 0.0, 0.0, 0.0],  # Point 1 
  [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]]  # Point 2 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 

Example in python :

# Move the torso and keep arms fixed in nao space 
# Warning: Needs a PoseInit before executing 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianTorsoArm2.py 
import motion 
 
space      = motion.SPACE_NAO 
coef       = 1.0                   # Speed motion 
times      = [coef, 2.0*coef, 3.0*coef, 4.0*coef] # seconds 
isAbsolute = False 
dx         = 0.04                  # translation axis X (meters) 
dy         = 0.04                  # translation axis Y (meters) 
 
# Motion of the Torso 
effector   = "Torso" 
path       = [ 
  [ 0.0, +dy, 0.0, 0.0, 0.0, 0.0], # Point 1 
  [ -dx, 0.0, 0.0, 0.0, 0.0, 0.0], # Point 2 
  [ 0.0, -dy, 0.0, 0.0, 0.0, 0.0], # Point 3 
  [ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]] # Point 4 
axisMask   = 63                    # control all the effector axis 
 
# Using 'post' makes this command execute in a another thread 
proxy.post.positionInterpolation(effector, space, path, 
                                 axisMask, times, isAbsolute) 
 
# Motion of Arms 
axisMask   = 7                     # control the position 
time       = 4.0*coef              # seconds 
 
# Arms have a null relative motion during all the torso motion 
path       = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Point 1 
 
# Motion of Right Arm 
effector   = "RArm" 
proxy.post.positionInterpolation(effector, space, path, 
                                 axisMask, time, isAbsolute) 
 
# Motion of Left Arm 
effector   = "LArm" 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, time, isAbsolute) 

Example in python :

# Example showing a path of two positions 
# Warning: Needs a PoseInit before executing 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianArm1.py 
import motion 
 
effector   = "LArm" 
space      = motion.SPACE_NAO 
axisMask   = 7          # just control position 
isAbsolute = False 
 
# Since we are in relative, the current position is zero 
currentPos = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] 
 
# define the changes relative to the current position 
dx         =  0.06      # translation axis X (meters) 
dy         =  0.06      # translation axis Y (meters) 
dz         =  0.00      # translation axis Z (meters) 
dwx        =  0.00      # rotation axis X (radians) 
dwy        =  0.00      # rotation axis Y (radians) 
dwz        =  0.00      # rotation axis Z (radians) 
targetPos  = [dx, dy, dz, dwx, dwy, dwz] 
 
# go to the target and back again 
path       = [targetPos, currentPos] 
times      = [2.0, 4.0] # seconds 
 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 

Example in python :

# Example showing a hand ellipsoid 
# Warning: Needs a PoseInit before executing 
# Example available: path/to/aldebaran-sdk/modules/src/examples/ 
#                    python/motion_cartesianArm2.py 
import motion 
 
effector   = "LArm" 
space      = motion.SPACE_NAO 
path       = [ 
  [0.0, -0.02, +0.00, 0.0, 0.0, 0.0],        # Point 1 
  [0.0, +0.00, +0.01, 0.0, 0.0, 0.0],        # Point 2 
  [0.0, +0.08, +0.00, 0.0, 0.0, 0.0],        # Point 3 
  [0.0, +0.00, -0.04, 0.0, 0.0, 0.0],        # Point 4 
  [0.0, -0.02, +0.00, 0.0, 0.0, 0.0],        # Point 5 
  [0.0, +0.00, +0.00, 0.0, 0.0, 0.0]]        # Point 6 
axisMask   = 7                               # just control position 
times      = [0.5, 1.0, 2.0, 3.0, 4.0, 4.5]  # seconds 
isAbsolute = False 
proxy.positionInterpolation(effector, space, path, 
                            axisMask, times, isAbsolute) 

void setAngles (const AL::ALValue& names, const AL::ALValue& angles, const float& fractionMaxSpeed)

Sets angles. This is a non-blocking call.

names

The name or names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

angles

One or more angles in radians

fractionMaxSpeed

The fraction of maximum speed to use

Example in python :

# Example showing how to set angles, using a fraction of max speed
names  = ['HeadYaw', 'HeadPitch']
angles  = [0.2, -0.2]
fractionMaxSpeed  = 0.2
proxy.setAngles(names, angles, fractionMaxSpeed)

Example in c++ :

// Example showing how to set angles, using a fraction of max speed
AL::ALValue names       = AL::ALValue::array("HeadYaw", "HeadPitch"); 
AL::ALValue angles      = AL::ALValue::array(0.2f, -0.2f); 
float fractionMaxSpeed  = 0.2f; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->setAngles(names, angles, fractionMaxSpeed); 

void setPosition (const string& chainName, const int& space, const vector<float>& position, const float& fractionMaxSpeed, const int& axisMask)

Moves an end-effector to the given position and orientation. This is a non-blocking call.

chainName

Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso"

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

position

6D position array (x,y,z,wx,wy,wz) in meters and radians

fractionMaxSpeed

The fraction of maximum speed to use

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

Example in python :

# Example showing how to set LArm Position, using a fraction of max speed 
import motion 
 
# After an InitPose 
 
chainName = "LArm" 
space     = motion.SPACE_TORSO 
useSensor = False 
 
# Get the current position of the chainName in the same space 
current = proxy.getPosition(chainName, space, useSensor) 
 
target  = [ 
current[0] + 0.1, 
current[1] + 0.1, 
current[2] + 0.1, 
current[3] + 0.0, 
current[4] + 0.0, 
current[5] + 0.0] 
 
fractionMaxSpeed = 0.5 
axisMask         = 7 # just control position 
 
proxy.setPosition(chainName, space, target, fractionMaxSpeed, axisMask) 

Example in python :

# Example showing how to set Torso Position, using a fraction of max speed
chainName        = "Torso" 
space            = 2 
position         = [0.0, 0.0, 0.25, 0.0, 0.0, 0.0] # Absolute Position
fractionMaxSpeed = 0.2 
axisMask         = 63 
proxy.setPosition(chainName, space, position, fractionMaxSpeed, axisMask)

Example in c++ :

// Example showing how to set Torso Position, using a fraction of max speed
std::string chainName  = "Torso"; 
int space              = 2; 
std::vector<float> position(6, 0.0f); // Absolute Position
position[2] = 0.25f; 
float fractionMaxSpeed = 0.2f; 
int axisMask           = 63; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->setPosition(chainName, space, position, fractionMaxSpeed, axisMask); 

void setTransform (const string& chainName, const int& space, const vector<float>& transform, const float& fractionMaxSpeed, const int& axisMask)

Moves an end-effector to the given position and orientation transform. This is a non-blocking call.

chainName

Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso"

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

transform

ALTransform arrays

fractionMaxSpeed

The fraction of maximum speed to use

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

Example in python :

# Example showing how to set Torso Transform, using a fraction of max speed
chainName        = "Torso" 
space            = 2 
transform        = [1.0, 0.0, 0.0, 0.00, 
                    0.0, 1.0, 0.0, 0.00, 
                    0.0, 0.0, 1.0, 0.25] # Absolute Position
fractionMaxSpeed = 0.2 
axisMask         = 63 
proxy.setTransform(chainName, space, transform, fractionMaxSpeed, axisMask)

Example in c++ :

// Example showing how to set Torso Transform, using a fraction of max speed
std::string chainName  = "Torso"; 
int space              = 2; 
std::vector<float> transform(12, 0.0f); // Absolute Position 
transform[0]  = 1.0f;  // 1.0f, 0.0f, 0.0f, 0.00f 
transform[5]  = 1.0f;  // 0.0f, 1.0f, 0.0f, 0.00f 
transform[10] = 1.0f;  // 0.0f, 0.0f, 1.0f, 0.25f 
transform[11] = 0.25f; 
float fractionMaxSpeed = 0.2f; 
int axisMask           = 63; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->setTransform(chainName, space, transform, fractionMaxSpeed, axisMask); 

void setStiffnesses (const AL::ALValue& names, const AL::ALValue& stiffnesses)

Sets the stiffness of one or more joints. This is a non-blocking call.

names

Names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

stiffnesses

One or more stiffnesses between zero and one.

Example in python :

# Example showing how to set the stiffness to 1.0.
# Beware, doing this could be dangerous, it is safer to use the 
#   stiffnessInterpolation method which takes a duration parameter.
names  = 'Body'
# If only one parameter is received, this is applied to all joints
stiffnesses  = 1.0
proxy.setStiffnesses(names, stiffnesses)

Example in c++ :

// Example showing how to set the stiffness to 1.0. 
// Beware, doing this could be dangerous, it is safer to use the 
// stiffnessInterpolation method which takes a duration parameter. 
std::string names  = "Body"; 
// If only one parameter is received, this is applied to all joints 
float stiffnesses  = 1.0f; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->setStiffnesses(names, stiffnesses); 

void stiffnessInterpolation (const AL::ALValue& names, const AL::ALValue& stiffnessLists, const AL::ALValue& timeLists)

Interpolates one or multiple joints to a target stiffness or along timed trajectories of stiffness. This is a blocking call.

names

Name or names of joints, chains, "Body", "BodyJoints" or "BodyActuators".

stiffnessLists

An stiffness, list of stiffnesses or list of list of stiffnesses

timeLists

A time, list of times or list of list of times.

Example in python :

# Example showing how to interpolate to maximum stiffness in 1 second
names  = 'Body'
stiffnessLists  = 0.0
timeLists  = 1.0
proxy.stiffnessInterpolation(names, stiffnessLists, timeLists)

Example in python :

# Example showing a stiffness trajectory for a single joint
names  = ['HeadYaw']
stiffnessLists  = [0.25,0.5,1.0]
timeLists  = [1.0,2.0,5.0]
proxy.stiffnessInterpolation(names, stiffnessLists, timeLists)

void transformInterpolation (const string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& duration, const bool& isAbsolute)

Moves an end-effector to the given position and orientation over time using homogenous transforms to describe the positions or changes. This is a blocking call.

chainName

Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso"

space

Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}.

path

Vector of ALTransform arrays

axisMask

Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both

duration

Vector of times in seconds corresponding to the path points

isAbsolute

If true, the movement is absolute else relative

Example in python :

# Example moving the left hand up a little using transforms
# Note that this is easier to do with positionInterpolation
chainName  = 'LArm'
# Defined in 'Torso' space
space  = 0
# We will use a single transform
# | R R R x |
# | R R R y |
# | R R R z |
# | 0 0 0 1 |
# Get the current transform, in 'Torso' space using
# the command angles.
initialTransform = proxy.getTransform('LArm',0, False)
# Copy the current transform
targetTransform = initialTransform
# add 2cm to the z axis, making the arm move upwards
targetTransform[11] = initialTransform[11] + 0.02
# construct a path with only one transform
path  = [targetTransform]
# The arm does not have enough degees of freedom
# to be able to constrain all the axes of movement,
# so here, we will choose an axis mask of 7, which
# will contrain position only
# x = 1, y = 2, z = 4, wx = 8, wy = 16, wz = 32
# 1 + 2 + 4 = 7
axisMask  = 7
# Allow three seconds for the movement
duration  = [3.0]
isAbsolute  = False
proxy.transformInterpolation(chainName, space, path,
axisMask, duration, isAbsolute)
finalTransform = proxy.getTransform('LArm',0, False)
print 'Initial', initialTransform
print 'Target', targetTransform
print 'Final', finalTransform

void updateTrackerTarget (const float& pTargetPositionWy, const float& pTargetPositionWz, const int& pTimeSinceDetectionMs, const bool& pUseOfWholeBody)

Update the target to follow by the head of NAO.
This function is mainly use by the tracker modules.

pTargetPositionWy

The target position wy in SPACE_NAO

pTargetPositionWz

The target position wz in SPACE_NAO

pTimeSinceDetectionMs

The time in Ms since the target was detected

pUseOfWholeBody

If true, the target is follow in cartesian space by the Head with whole Body constraints.

void setMotionConfig (const AL::ALValue& config)

Internal Use.

config

Internal: An array of ALValues [i][0]: name, [i][1]: value

AL::ALValue getTaskList ()

Gets an ALValue structure describing the tasks in the Task List

Returns

An ALValue containing an ALValue for each task. The inner ALValue contains: Name, MotionID, BrokerID, Priority, Resources

Example in python :

# Example showing how to get the current task list
# We will create a task first, so that we see a result
proxy.post.angleInterpolation('HeadYaw', 1.0, 1.0, True)
time.sleep(0.1)
print 'Tasklist', proxy.getTaskList()

bool areResourcesAvailable (const vector<string>& resourceNames)

Returns true if the resources are available.

resourceNames

A vector of resource names such as joints

Returns

True if the resources are available

void killTasksUsingResources (const vector<string>& resourceNames)

Kills all tasks that use any of the resources given.

resourceNames

A vector of resource joint names

AL::ALValue getWalkArmsEnable ()

Gets if Arms Motions are enabled during the Walk Process.

Returns

True Arm Motions are controlled by the Walk Task.

Example in python :

# Example showing how to get the enabled flags for the arms 
result = proxy.getWalkArmsEnable() 
print 'LeftArmEnabled: ', result[0] 
print 'RightArmEnabled: ', result[1] 

void setWalkArmsEnable (const bool& leftArmEnable, const bool& rightArmEnable)

Sets if Arms Motions are enabled during the Walk Process.

leftArmEnable

if true Left Arm motions are controlled by the Walk Task

rightArmEnable

if true Right Arm mMotions are controlled by the Walk Task

Example in python :

# Example showing how to disable left arm motions during a walk
leftArmEnable  = False
rightArmEnable  = True
proxy.setWalkArmsEnable(leftArmEnable, rightArmEnable)
# disable also right arm motion after 10 seconds
time.sleep(10)
rightArmEnable  = False
proxy.setWalkArmsEnable(leftArmEnable, rightArmEnable)

void setWalkTargetVelocity (const float& x, const float& y, const float& theta, const float& frequency)

Makes Nao walk at the given velocity. This is a non-blocking call.

x

Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0]

y

Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0]

theta

Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0]

frequency

Fraction of MaxStepFrequency [0.0 to 1.0]

Example in python :

# Example showing the use of setWalkTargetVelocity
# The parameters are fractions of the maximums
# Here we are asking for full speed forwards
x  = 1.0
y  = 0.0
theta  = 0.0
frequency  = 1.0
proxy.setWalkTargetVelocity(x, y, theta, frequency)
# If we don't send another command, he will walk forever
# Lets make him slow down(step length) and turn after 10 seconds
time.sleep(10)
x = 0.5
theta = 0.6
proxy.setWalkTargetVelocity(x, y, theta, frequency)
# Lets make him slow down(frequency) after 5 seconds
time.sleep(5)
frequency  = 0.5
proxy.setWalkTargetVelocity(x, y, theta, frequency)
time.sleep(10)
proxy.setWalkTargetVelocity(0.0, 0.0, 0.0, frequency)
# Note that at any time, you can use a walkTo command
# to walk a precise distance. The last command received,
# of velocity or position always wins

Example in python :

################################
# WALK FOOT CONTACT PROTECTION #
################################
# This is a protection around the walk process.
# If there is no Foot Contact (based on FSR), the walk will be
# killed or prevented from launching.
# By default, this option is activated.

# If you want disable this option use :
proxy.setMotionConfig([["ENABLE_FOOT_CONTACT_PROTECTION",False]]) 

# or modify the default value in the ALMotion preference file
# on the robot: \opt\naoqi\preferences\ALMotion.xml

Example in python :

#############################
# WALK STIFFNESS PROTECTION #
#############################
# This is a protection around the walk process.
# If one joint of the legs has a Stiffness equal
# or less than 0.6, the walk will be killed or prevented
# from launching.
# By default, this option is activated.

# If you want disable this option use :
proxy.setMotionConfig([["ENABLE_STIFFNESS_PROTECTION",False]]) 

# or modify the default value in the ALMotion preference file
# on the robot: \opt\naoqi\preferences\ALMotion.xml

void stepTo (const string& legName, const float& x, const float& y, const float& theta)

Makes Nao do a single step. This is a blocking call.

legName

name of the leg to move('LLeg'or 'RLeg')

x

Position along X axis of the leg relative to the other Leg in meters. Must be less than MaxStepX

y

Position along Y axis of the leg relative to the other Leg in meters. Must be less than MaxStepY

theta

Orientation round Z axis of the leg relative to the other leg in radians. Must be less than MaxStepX

Example in python :

# A small step forwards and anti-clockwise with the left foot
Leg = 'LLeg'
X = 0.02
Y = 0.0
Theta = 0.30
proxy.stepTo(Leg, X, Y, Theta)
# block script until stepTo task is not finished

Example in python :

########
# NOTE #
########
# If stepTo() method does nothing on the robot,
# please refer to the special walk protection in the
# setWalkTragetVelocity() method description below.

void walkTo (const float& x, const float& y, const float& theta)

Makes Nao walk to the given relative Position. This is a blocking call.

x

Distance along the X axis in meters.

y

Distance along the Y axis in meters.

theta

Rotation around the Z axis in radians [-3.1415 to 3.1415].

Example in python :

# Example showing the walkTo command 
# as length of path is less than 0.4m 
# the path will be an SE3 interpolation 
# The units for this command are meters and radians 
x  = 0.2 
y  = 0.2 
# pi/2 anti-clockwise (90 degrees) 
theta  = 1.5709 
proxy.walkTo(x, y, theta) 
# Will block until walk Task is finished 
 
# Example showing the walkTo command 
# as length of path is more than 0.4m 
# the path will be follow a dubins curve 
# The units for this command are meters and radians 
x  = -0.1 
y  = -0.7 
theta  = 0.0 
proxy.walkTo(x, y, theta) 

Example in python :

########
# NOTE #
########
# If walkTo() method does nothing on the robot,
# please refer to special walk protection in the
# setWalkTragetVelocity() method description below.

Example in c++ :

// Example showing the walkTo command 
// as length of path is less than 0.4m 
// the path will be an SE3 interpolation 
// The units for this command are meters and radians 
float x  = 0.2f; 
float y  = 0.2f; 
// pi/2 anti-clockwise (90 degrees) 
float theta = 1.5709f; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->walkTo(x, y, theta); 
// Will block until walk Task is finished 
 
// Example showing the walkTo command 
// as length of path is more than 0.4m 
// the path will be follow a dubins curve 
// The units for this command are meters and radians 
x  = -0.1f; 
y  = -0.7f; 
theta  = 0.0f; 
motion->walkTo(x, y, theta); 

void waitUntilWalkIsFinished ()

Waits until the WalkTask is finished: This method can be used to block your script/code execution until the walk task is totally finished.

Example in python :

# Example showing how to use waitUntilWalkIsFinished. 
 
# Start a walk 
x = 1.0 
y = 0.0 
theta = 0.0 
proxy.post.walkTo(x, y, theta) 
 
# Wait for it to finish  
proxy.waitUntilWalkIsFinished()  
 
# Then do something else  

Example in c++ :

// Example showing how to use waitUntilWalkIsFinished. 
 
// Start a walk 
float x = 1.0f; 
float y = 0.0f; 
float theta = 0.0f; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->walkTo(x, y, theta); 
 
// Wait for it to finish  
motion->waitUntilWalkIsFinished(); 
 
// Then do something else  

bool walkIsActive ()

Return True if Walk is Active.

Returns

True Arm Motions are controlled by the Walk Task.

Example in python :

# Example showing how to use walk is active. 
# start a 1 meter walk 
proxy.post.walkTo(1.0, 0.0, 0.0, 1.0) 

while proxy.walkIsActive(): 
# do something 

# sleep a little 
time.sleep(1) 

# when finished do something else 

Example in c++ :

// Example showing how to use walk is active. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
bool walkIsActive = motion->walkIsActive(); 

void killWalk ()

Emergency Stop on Walk task: This method will end the walk task brutally, without attempting to return to a balanced state. If Nao has one foot in the air, he could easily fall.

Example in python :

# End the walk suddenly (around 20ms) 
proxy.killWalk() 

Example in c++ :

// Example showing how to use Emergency Stop on Walk task. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->killWalk(); 

void wbEnable (const bool& isEnabled)

UserFriendly Whole Body API: enable Whole Body Balancer. It's a Generalized Inverse Kinematics which deals with cartesian control, balance, redundancy and task priority. The main goal is to generate and stabilized consistent motions without precomputed trajectories and adapt nao's behaviour to the situation. The generalized inverse kinematic problem takes in account equality constraints (keep foot fix), inequality constraints (joint limits, balance, ...) and quadratic minimization (cartesian / articular desired trajectories). We solve each step a quadratic programming on the robot.

isEnabled

Active / Disactive Whole Body Balancer.

Example in python :

# Example showing how to active Whole Body Balancer.
isEnabled = True
proxy.wbEnable(isEnabled)

Example in c++ :

// Example showing how to active Whole Body Balancer.
bool isEnabled = true; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbEnable(isEnabled); 

void wbEnableEffectorControl (const string& effectorName, const bool& isEnabled)

UserFriendly Whole Body API: enable whole body cartesian control of an effector.

effectorName

Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position.

isEnabled

Active / Disactive Effector Control.

Example in python :

# Example showing how to active Head tracking.
effectorName = 'Head' 
isEnabled = True 
proxy.wbEnableEffectorControl(effectorName, isEnabled)

Example in c++ :

// Example showing how to active Head tracking.
std::string effectorName = "Head"; 
bool isEnabled = true; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbEnableEffectorControl(effectorName, isEnabled); 

void wbSetEffectorControl (const string& effectorName, const AL::ALValue& targetCoordinate)

UserFriendly Whole Body API: set new target for controlled effector. This is a non-blocking call.

effectorName

Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position.

targetCoordinate

"Head" is controlled in rotation (WX, WY, WZ). "LArm" and "RArm" are controlled in position (X, Y, Z). TargetCoordinate must be absolute and expressed in SPACE_NAO. If the desired position/orientation is unfeasible, target is resize to the nearest feasible motion.

Example in python :

# Example showing how to set orientation target for Head tracking. 
effectorName = "Head" 
targetCoordinate = [0.1, 0.0, 0.0] 
proxy.wbSetEffectorControl(effectorName, targetCoordinate) 

Example in c++ :

// Example showing how to set orientation target for Head tracking. 
std::string effectorName = "Head"; 
AL::ALValue targetCoordinate = AL::ALValue::array(0.1f, 0.0f, 0.0f); 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbSetEffectorControl(effectorName, targetCoordinate); 

void wbFootState (const string& stateName, const string& supportLeg)

UserFriendly Whole Body API: set the foot state: fixed foot, constrained in a plane or free.

stateName

Name of the foot state. "Fixed" set the foot fixed. "Plane" constrained the Foot in the plane. "Free" set the foot free.

supportLeg

Name of the foot. "LLeg", "RLeg" or "Legs".

Example in python :

# Example showing how to fix the feet. 
stateName = "Fixed" 
supportLeg = "Legs" 
proxy.wbFootState(stateName, supportLeg) 

Example in c++ :

// Example showing how to fix the feet. 
std::string stateName = "Fixed"; 
std::string supportLeg = "Legs"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbFootState(stateName, supportLeg); 

Example in python :

# Example showing how to fix the left leg and constrained in a plane the right leg.
proxy.wbFootState("Fixed", "LLeg") 
proxy.wbFootState("Plane", "RLeg") 

Example in c++ :

// Example showing how to fix the left leg and constrained in a plane the right leg. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbFootState("Fixed", "LLeg"); 
motion->wbFootState("Plane", "RLeg"); 

Example in python :

# Example showing how to fix the left leg and keep free the right leg. 
proxy.wbFootState("Fixed", "LLeg") 
proxy.wbFootState("Free", "RLeg") 

Example in c++ :

// Example showing how to fix the left leg and keep free the right leg. 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbFootState("Fixed", "LLeg"); 
motion->wbFootState("Free", "RLeg"); 

void wbEnableBalanceConstraint (const bool& isEnable, const string& supportLeg)

UserFriendly Whole Body API: enable to keep balance in support polygon.

isEnable

Enable Nao to keep balance.

supportLeg

Name of the support leg: "Legs", "LLeg", "RLeg".

Example in python :

# Example showing how to Constraint Balance Motion. 
isEnable   = True 
supportLeg = "Legs" 
proxy.wbEnableBalanceConstraint(isEnable, supportLeg) 

Example in c++ :

// Example showing how to Constraint Balance Motion. 
bool isEnable = true; 
std::string supportLeg  = "Legs"; 
AL::ALPtr<AL::ALMotionProxy> motion = getParentBroker()->getMotionProxy(); 
motion->wbEnableBalanceConstraint(isEnable, supportLeg); 


Methods inherited from ALModule

void exit ()

Exits and unregisters the module.

string version ()

Returns the version of the module.

Returns

A string containing the version of the module.

bool ping ()

Just a ping. Always returns true

Returns

returns true

vector<string> getMethodList ()

Retrieves the module's method list.

Returns

An array of method names.

AL::ALValue getMethodHelp (const string& methodName)

Retrieves a method's description.

methodName

The name of the method.

Returns

A structure containing the method's description.

AL::ALValue getModuleHelp ()

Retrieves the module's description.

Returns

A structure describing the module.

string getBrokerName ()

Gets the name of the parent broker.

Returns

The name of the parent broker.

string getUsage (const string& name)

Gets the method usage string. This summarise how to use the method.

name

The name of the method.

Returns

A string that summarises the usage of the method.


Example Code

Example in python :

import naoqi
from naoqi import ALProxy
# configure the IP of your robot
IP = "127.0.0.1"
PORT = 9559
# create a proxy to ALMotion
proxy = ALProxy("ALMotion", IP, PORT)
# print the current state
print proxy.getSummary()
# see method examples for possible calls

Copyright © 2010 Aldebaran Robotics - All rights reserved