Locomotion control API

NAOqi Motion - Overview | API | robot position Tutorial


Method list

class ALMotionProxy
void ALMotionProxy::move(const float& x, const float& y, const float& theta)

There are two overloads of this function:

Makes the robot move at the given velocity, expressed in FRAME_ROBOT. This is a non-blocking call.

Parameters:
  • x – velocity along X-axis, in meters per second. Use negative values for backward motion
  • y – velocity along Y-axis, in meters per second. Use positive values to go to the left
  • theta – velocity around Z-axis, in radians per second. Use negative values to turn clockwise.
void ALMotionProxy::move(const float& x, const float& y, const float& theta, const AL::ALValue moveConfig)

Makes the robot move at the given velocity, expressed in FRAME_ROBOT, with a move configuration. This is a non-blocking call.

Parameters:
  • x – velocity along X-axis, in meters per second. Use negative values for backward motion
  • y – velocity along Y-axis, in meters per second. Use positive values to go to the left
  • theta – velocity around Z-axis, in radians per second. Use negative values to turn clockwise.
  • moveConfig – An ALValue with the custom move configuration.
void ALMotionProxy::moveToward(const float& x, const float& y, const float& theta)

There are two overloads of this function:

Makes the robot move at the given normalized velocity, expressed in FRAME_ROBOT. This is a non-blocking call.

Parameters:
  • x – normalized, unitless, velocity along X-axis. +1 and -1 correspond to the maximum velocity in the forward and backward directions, respectively.
  • y – normalized, unitless, velocity along Y-axis. +1 and -1 correspond to the maximum velocity in the left and right directions, respectively.
  • theta – normalized, unitless, velocity around Z-axis. +1 and -1 correspond to the maximum velocity in the counterclockwise and clockwise directions, respectively.
void ALMotionProxy::moveToward(const float& x, const float& y, const float& theta, const AL::ALValue moveConfig)

Makes the robot move at the given normalized velocity, expressed in FRAME_ROBOT, with a move configuration. This is a non-blocking call.

Parameters:
  • x – normalized, unitless, velocity along X-axis. +1 and -1 correspond to the maximum velocity in the forward and backward directions, respectively.
  • y – normalized, unitless, velocity along Y-axis. +1 and -1 correspond to the maximum velocity in the left and right directions, respectively.
  • theta – normalized, unitless, velocity around Z-axis. +1 and -1 correspond to the maximum velocity in the counterclockwise and clockwise directions, respectively.
  • moveConfig – An ALValue with the custom move configuration.
void ALMotionProxy::setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency)

There are three overloads of this function:

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

Parameters:
  • 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]

almotion_setwalktargetvelocity.py

import sys
# -*- encoding: UTF-8 -*-

import time
from naoqi import ALProxy

def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # 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
    motionProxy.setWalkTargetVelocity(x, y, theta, frequency)

    # If we don't send another command, he will move forever
    # Lets make him slow down(step length) and turn after 3 seconds
    time.sleep(3)
    x = 0.5
    theta = 0.6
    motionProxy.setWalkTargetVelocity(x, y, theta, frequency)

    # Lets make him slow down(frequency) after 3 seconds
    time.sleep(3)
    frequency  = 0.5
    motionProxy.setWalkTargetVelocity(x, y, theta, frequency)

    # Lets make him stop after 3 seconds
    time.sleep(3)
    motionProxy.stopMove()
    # Note that at any time, you can use a moveTo command
    # to run a precise distance. The last command received,
    # of velocity or position always wins


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_setwalktargetvelocity.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& feetGaitConfig)

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

Parameters:
  • 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]
  • feetGaitConfig – An ALValue with the custom gait configuration for both feet
void ALMotionProxy::setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& leftFootGaitConfig, const AL::ALValue& rightFootGaitConfig)

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

Parameters:
  • 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]
  • leftFootGaitConfig – An ALValue with custom gait configuration for the left foot
  • rightFootGaitConfig – An ALValue with custom gait configuration for the right foot
void ALMotionProxy::moveTo(const float& x, const float& y, const float& theta)

There are four overloads of this function:

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT. This is a blocking call.

Parameters:
  • 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].

almotion_moveto.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>
#include <alproxies/alrobotpostureproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_moveto robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);
  AL::ALRobotPostureProxy robotPosture(robotIp);

  robotPosture.goToPosture("StandInit", 0.5f);

  // Example showing the moveTo 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;
  motion.moveTo(x, y, theta);
  // Will block until walk Task is finished

  // Example showing the moveTo 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.5f;
  theta  = 0.0f;
  motion.moveTo(x, y, theta);

  return 0;
}

almotion_moveto.py

# -*- encoding: UTF-8 -*-

import sys
import math
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # Example showing the moveTo command
    # The units for this command are meters and radians
    x  = 0.2
    y  = 0.2
    theta  = math.pi/2
    motionProxy.moveTo(x, y, theta)
    # Will block until move Task is finished

    ########
    # NOTE #
    ########
    # If moveTo() method does nothing on the robot,
    # read the section about walk protection in the
    # Locomotion control overview page.


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_moveto.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::moveTo(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig)

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT, with custom move configuration. This is a blocking call.

Parameters:
  • 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].
  • moveConfig – An ALValue with the custom move configuration.
void ALMotionProxy::moveTo(const AL::ALValue& controlPoints)

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points. This is a blocking call.

Parameters:
  • controlPoint – An ALValue with all the control points [[x1,y1,theta1], ..., [xN,yN,thetaN]
void ALMotionProxy::moveTo(const AL::ALValue& controlPoints, const AL::ALValue& moveConfig)

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points with custom move configuration. This is a blocking call.

Parameters:
  • controlPoints – An ALValue with all the control points [[x1,y1,theta1], ..., [xN,yN,thetaN]
  • moveConfig – An ALValue with the custom move configuration.
void ALMotionProxy::walkTo(const float& x, const float& y, const float& theta)

Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.

Makes NAO walk to the given pose in the ground plane, relative to FRAME_ROBOT. This is a blocking call.

Parameters:
  • 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].
void ALMotionProxy::walkTo(const float& x, const float& y, const float& theta, const AL::ALValue& feetGaitConfig)

Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT, with custom gait parameters. This is a blocking call.

Parameters:
  • 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].
  • feetGaitConfig – An ALValue with the custom gait configuration for both feet.
void ALMotionProxy::walkTo(const AL::ALValue& controlPoints)

Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.

Makes NAO move to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points. This is a blocking call.

Parameters:
  • controlPoints – An ALValue with all the control points [[x1,y1,theta1], ..., [xN,yN,thetaN]
void ALMotionProxy::walkTo(const AL::ALValue& controlPoints, const AL::ALValue& feetGaitConfig)

Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.

Makes NAO walk to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points with custom move configuration. This is a blocking call.

Parameters:
  • controlPoints – An ALValue with all the control points [[x1,y1,theta1], ..., [xN,yN,thetaN]
  • feetGaitConfig – An ALValue with the custom gait configuration for both feet
void ALMotionProxy::setFootSteps(const std::vector<std::string>& legName, const AL::ALValue& footSteps, const std::vector<float>& timeList, const bool& clearExisting)

Makes NAO do foot step planner. This is a non-blocking call.

Parameters:
  • legName – name of the leg to move(‘LLeg’or ‘RLeg’)
  • footSteps – [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta]
  • timeList – time list of each foot step
  • clearExisting – Clear existing foot steps.

almotion_setfootsteps.py

import sys
# -*- encoding: UTF-8 -*-

import time
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # A small step forwards and anti-clockwise with the left foot
    legName  = ["LLeg"]
    X        = 0.2
    Y        = 0.1
    Theta    = 0.3
    footSteps = [[X, Y, Theta]]
    timeList = [0.6]
    clearExisting = False
    motionProxy.setFootSteps(legName, footSteps, timeList, clearExisting)

    time.sleep(1.0)

    # A small step forwards and anti-clockwise with the left foot
    legName = ["LLeg", "RLeg"]
    X       = 0.2
    Y       = 0.1
    Theta   = 0.3
    footSteps = [[X, Y, Theta], [X, -Y, Theta]]
    timeList = [0.6, 1.2]
    clearExisting = False
    motionProxy.setFootSteps(legName, footSteps, timeList, clearExisting)


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_setfootsteps.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::setFootStepsWithSpeed(const std::vector<std::string>& legName, const AL::ALValue& footSteps, const std::vector<float>& fractionMaxSpeed, const bool& clearExisting)

Makes NAO do foot step planner with speed. This is a blocking call.

Parameters:
  • legName – name of the leg to move(‘LLeg’or ‘RLeg’)
  • footSteps – [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta]
  • fractionMaxSpeed – speed of each foot step. Must be between 0 and 1.
  • clearExisting – Clear existing foot steps.

almotion_setfootstepswithspeed.py

import sys
# -*- encoding: UTF-8 -*-

import time
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # A small step forwards and anti-clockwise with the left foot
    legName = ["LLeg"]
    X       = 0.2
    Y       = 0.1
    Theta   = 0.3
    footSteps = [[X, Y, Theta]]
    fractionMaxSpeed = [1.0]
    clearExisting = False
    motionProxy.setFootStepsWithSpeed(legName, footSteps, fractionMaxSpeed, clearExisting)

    time.sleep(0.5)

    # A small step forwards and anti-clockwise with the left foot
    legName = ["LLeg", "RLeg"]
    X       = 0.2
    Y       = 0.1
    Theta   = 0.3
    footSteps = [[X, Y, Theta], [X, -Y, Theta]]
    fractionMaxSpeed = [1.0, 1.0]
    clearExisting = False
    motionProxy.setFootStepsWithSpeed(legName, footSteps, fractionMaxSpeed, clearExisting)


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_setfootstepswithspeed.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
AL::ALValue ALMotionProxy::getFootSteps()

Get the actual foot steps vector. This is a non-blocking call.

Returns:An ALValue containing three vector with:
[
  [The actual position of the left and right foot steps in world frame]
  [The unChangeable foot steps]
  [The changeable foot steps]
]

In more details:

[
  [
    [(float) LFootWorld_X, (float) LFootWorld_Y, (float) LFootWorld_Theta],
    [(float) RFootWorld_X, (float) RFootWorld_Y, (float) RFootWorld_Theta]
  ]
  [
    [(std::string) LegName, (float) Time, [(float) Move_X, (float) Move_Y, (float) Move_Y],
    [...],
    [(std::string) LegName, (float) Time, [(float) Move_X, (float) Move_Y, (float) Move_Y]
  ]
  [
    [(std::string) LegName, (float) Time, [(float) Move_X, (float) Move_Y, (float) Move_Y],
    [...],
    [(std::string) LegName, (float) Time, [(float) Move_X, (float) Move_Y, (float) Move_Y]
  ]
]

Each move of foot step is relative to the previous location of the opposite foot step. For example, a foot step move of LFoot will be relative to the last position of the RFoot.

If you use setFootSteps or setFootStepsWithSpeed with clearExisting parameter equal true, walk engine execute unchangeable foot step and remove the other.

almotion_getfootsteps.py

# -*- encoding: UTF-8 -*-

import sys
import time
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    #####################################
    # A small example using getFootSteps
    #####################################

    # First call of move API
    # with post prefix to not be bloquing here.
    motionProxy.post.moveTo(0.3, 0.0, 0.5)

    # wait that the move process start running
    time.sleep(1.0)

    # get the foot steps vector
    footSteps = motionProxy.getFootSteps()

    # print the result
    leftFootWorldPosition = footSteps[0][0]
    print "leftFootWorldPosition:"
    print leftFootWorldPosition
    print ""

    rightFootWorldPosition = footSteps[0][1]
    print "rightFootWorldPosition:"
    print rightFootWorldPosition
    print ""

    footStepsUnchangeable = footSteps[1]
    print "Unchangeable:"
    print footStepsUnchangeable
    print ""

    footStepsChangeable   = footSteps[2]
    print "Changeable:"
    print footStepsChangeable
    print ""

if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_getfootsteps.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::walkInit()

Deprecated since version 1.14: use ALMotionProxy::moveInit() instead.

void ALMotionProxy::moveInit()

Initializes the move process. Checks the robot pose and takes a right posture. This is blocking called.

almotion_moveinit.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>
#include <alproxies/alrobotpostureproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_moveinit robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);
  AL::ALRobotPostureProxy robotPosture(robotIp);
  robotPosture.goToPosture("Stand", 0.5f);

  // Example showing how Initialize move process.
  motion.moveInit();

  return 0;
}

almotion_moveinit.py

# -*- encoding: UTF-8 -*-

import sys
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("Stand", 0.5)

    # Example showing how Initialize move process.
    motionProxy.moveInit()


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_moveinit.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::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.

Deprecated since version 1.14: use ALMotionProxy::waitUntilMoveIsFinished() instead.

void ALMotionProxy::waitUntilMoveIsFinished()

Waits until the MoveTask is finished: this method can be used to block your script/code execution until the move task is totally finished.

almotion_waituntilmoveisfinished.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>
#include <alproxies/alrobotpostureproxy.h>
#include <qi/os.hpp>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_waituntilmoveisfinished robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);
  AL::ALRobotPostureProxy robotPosture(robotIp);

  robotPosture.goToPosture("StandInit", 0.5f);

  // Example showing how to use waitUntilMoveIsFinished.
  // Start a walk
  float x = 0.10f;
  float y = 0.0f;
  float theta = 0.0f;
  motion.post.moveTo(x, y, theta);

  // Wait for it to finish
  motion.waitUntilMoveIsFinished();
  // Then do something else

  return 0;
}

almotion_waituntilmoveisfinished.py

# -*- encoding: UTF-8 -*-

import sys
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # Example showing how to use waitUntilMoveIsFinished.

    # Start a move
    x = 0.2
    y = 0.0
    theta = 0.0
    motionProxy.post.moveTo(x, y, theta)

    # Wait for it to finish
    motionProxy.waitUntilMoveIsFinished()

    # Then do something else
    print "Move is finished"


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_waituntilmoveisfinished.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
bool ALMotionProxy::walkIsActive()
Returns:True if Walk is Active.

Deprecated since version 1.14: use ALMotionProxy::moveIsActive() instead.

bool ALMotionProxy::moveIsActive()
Returns:True if move is Active.

almotion_moveisactive.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_moveisactive robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example showing how to use walk is active.
  bool moveIsActive = motion.moveIsActive();

  std::cout << "Move is active: " << moveIsActive << std::endl;

  return 0;
}

almotion_moveisactive.py

# -*- encoding: UTF-8 -*-

import sys
import time
from naoqi import ALProxy

def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # Example showing how to use walk is active.
    # start a 0.2 meter walk
    motionProxy.post.moveTo(0.2, 0.0, 0.0)

    while motionProxy.moveIsActive():
        # do something
        print "Move is active"

    # sleep a little
    time.sleep(1)

    # when finished do something else


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_advancedcreaterotation.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::stopWalk()

Stops Walk task at next double support: this method will end the walk task less brutally than killWalk but more quickly than setWalkTargetVelocity(0.0, 0.0, 0.0, pFrequency).

Deprecated since version 1.14: use ALMotionProxy::stopMove() instead.

void ALMotionProxy::stopMove()

Stops Move task at next double support: this method will end the move task less brutally than killMove but more quickly than setWalkTargetVelocity(0.0, 0.0, 0.0, pFrequency).

AL::ALValue ALMotionProxy::getFootGaitConfig(const std::string& config)

Gets the foot Gait config (“MaxStepX”, “MaxStepY”, “MaxStepTheta”, “MaxStepFrequency”, “StepHeight”, “TorsoWx”, “TorsoWy”).

Deprecated since version 1.14: use ALMotionProxy::getMoveConfig() instead.

Parameters:
  • config – a string should be “Max”, “Min”, “Default”
Returns:

An ALValue with the following form

[ ["MaxStepX", value],
  ["MaxStepY", value],
  ["MaxStepTheta", value],
  ["MaxStepFrequency", value],
  ["StepHeight", value],
  ["TorsoWx", value],
  ["TorsoWy", value]
]

AL::ALValue ALMotionProxy::getMoveConfig(const std::string& config)

Gets the move config (“MaxStepX”, “MaxStepY”, “MaxStepTheta”, “MaxStepFrequency”, “StepHeight”, “TorsoWx”, “TorsoWy”).

Parameters:
  • config – a string should be “Max”, “Min”, “Default”
Returns:

An ALvalue with the move config. with the following form

[ ["MaxStepX", value],
  ["MaxStepY", value],
  ["MaxStepTheta", value],
  ["MaxStepFrequency", value],
  ["StepHeight", value],
  ["TorsoWx", value],
  ["TorsoWy", value]
]

Example in python:

# Example showing how to get and play with foot gait config
# a getFootConfig could be directly use in a walk method
# WARNING : be aware that Max and Min are extrem values and could create
#           some strange walk behavior

import time

proxy.moveInit()
proxy.setWalkTargetVelocity(1.0, 0.0, 0.0, 1.0, proxy.getMoveConfig("Default"),
                                                proxy.getMoveConfig("Min"))
time.sleep(3.0)
proxy.stopMove()
std::vector<float> ALMotionProxy::getRobotPosition(const bool& useSensors)

Gets the World Absolute Robot Position.

Parameters:
  • useSensors – If true, use the MRE sensor values
Returns:

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

almotion_getrobotposition.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_getrobotposition robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

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

  std::cout << "Robot position is: " << result << std::endl;

  return 0;
}

almotion_getrobotposition.py

# -*- encoding: UTF-8 -*-

import sys
from naoqi import ALProxy
import almath


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

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

    # Example showing how to use this information to know the robot's diplacement.
    useSensorValues = False
    initRobotPosition = almath.Pose2D(motionProxy.getRobotPosition(useSensorValues))

    # Make the robot move
    motionProxy.moveTo(0.1, 0.0, 0.2)

    endRobotPosition = almath.Pose2D(motionProxy.getRobotPosition(useSensorValues))

    # Compute robot's' displacement
    robotMove = almath.pose2DInverse(initRobotPosition)*endRobotPosition
    print "Robot Move:", robotMove


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_getrobotposition.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
std::vector<float> ALMotionProxy::getNextRobotPosition()

Gets the World Absolute next Robot Position.

When no walk process active, getNextRobotPosition() = getRobotPosition().

Else getNextRobotPosition return the position of the robot after the unchangeable foot steps.

Returns:A vector containing the World Absolute next Robot position.(Absolute Position X, Absolute Position Y, Absolute Angle Theta (Wz))

almotion_getnextrobotposition.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_getnextrobotposition robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example showing how to get a simplified next robot position in world.
  std::vector<float> result = motion.getNextRobotPosition();

  std::cout << "Next robot position is: " << result << std::endl;

  return 0;
}

almotion_getnextrobotposition.py

# -*- encoding: UTF-8 -*-

import sys
import time
from naoqi import ALProxy
import almath as m #python's wrapping of almath

def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    # Example showing how to get a simplified robot position in world.
    result = motionProxy.getNextRobotPosition()
    print "Next Robot Position", result

    # Example showing how to use this information to know the robot's diplacement
    # during the move process.

    # Make the robot move
    motionProxy.post.moveTo(0.6, 0.0, 0.5) # No blocking due to post called
    time.sleep(1.0)
    initRobotPosition = m.Pose2D(motionProxy.getNextRobotPosition())

    # Make the robot move
    motionProxy.moveTo(0.1, 0.0, 0.2)

    endRobotPosition = m.Pose2D(motionProxy.getNextRobotPosition())

    # Compute robot's' displacement
    robotMove = m.pose2DInverse(initRobotPosition)*endRobotPosition
    print "Robot Move :", robotMove


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_getnextrobotposition.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
std::vector<float> ALMotionProxy::getRobotVelocity()

Gets the World Absolute Robot Velocity.

Returns:A vector containing the World Absolute Robot Velocity. (Absolute Velocity Translation X [m.s-1], Absolute Velocity Translation Y[m.s-1], Absolute Velocity Rotation WZ [rd.s-1])

almotion_getrobotvelocity.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_getrobotvelocity robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

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

  std::cout << "Robot velocity is: " << result << std::endl;

  return 0;
}

almotion_getrobotvelocity.py

# -*- encoding: UTF-8 -*-

import sys
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

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


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_getrobotvelocity.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
AL::ALValue ALMotionProxy::getWalkArmsEnabled()

Gets if Arms Motions are enabled during the Walk Process.

Returns:True Arm Motions are controlled by the Walk Task.

almotion_getwalkarmsenabled.cpp

#include <iostream>
#include <alproxies/almotionproxy.h>

int main(int argc, char **argv)
{
  std::string robotIp = "127.0.0.1";

  if (argc < 2) {
    std::cerr << "Usage: almotion_getwalkarmsenable robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example showing how to get the enabled flags for the arms
  AL::ALValue result = motion.getWalkArmsEnabled();
  std::cout << "LeftArmEnabled: " << result[0] << std::endl;
  std::cout << "RightArmEnabled: " << result[1] << std::endl;

  return 0;
}

almotion_getwalkarmsenable.py

# -*- encoding: UTF-8 -*-

import sys
from naoqi import ALProxy


def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

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


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_getwalkarmsenabled.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)
void ALMotionProxy::setWalkArmsEnabled(const bool& leftArmEnable, const bool& rightArmEnable)

Sets if Arms Motions are enabled during the Walk Process.

Parameters:
  • leftArmEnable – if true Left Arm motions are controlled by the Walk Task
  • rightArmEnable – if true Right Arm motions are controlled by the Walk Task

almotion_setwalkarmsenabled.py

# -*- encoding: UTF-8 -*-

import sys
import time
from naoqi import ALProxy

def main(robotIP):
    PORT = 9559

    try:
        motionProxy = ALProxy("ALMotion", robotIP, PORT)
    except Exception,e:
        print "Could not create proxy to ALMotion"
        print "Error was: ",e
        sys.exit(1)

    try:
        postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)
    except Exception, e:
        print "Could not create proxy to ALRobotPosture"
        print "Error was: ", e

    # Send NAO to Pose Init
    postureProxy.goToPosture("StandInit", 0.5)

    x          = 0.6
    y          = 0.0
    theta      = 0.0
    frequency  = 1.0
    motionProxy.setWalkTargetVelocity(x, y, theta, frequency)

    time.sleep(2.0)

    # Example showing how to disable left arm motions during a move
    leftArmEnable  = False
    rightArmEnable  = True
    motionProxy.setWalkArmsEnabled(leftArmEnable, rightArmEnable)
    print "Disabled left arm"

    # disable also right arm motion after 1 seconds
    time.sleep(1.0)
    rightArmEnable  = False
    motionProxy.setWalkArmsEnabled(leftArmEnable, rightArmEnable)
    print "Disabled right arm"

    time.sleep(1.0)

    motionProxy.stopMove()

    leftArmEnable  = True
    rightArmEnable  = True
    motionProxy.setWalkArmsEnabled(leftArmEnable, rightArmEnable)


if __name__ == "__main__":
    robotIp = "127.0.0.1"

    if len(sys.argv) <= 1:
        print "Usage python almotion_setwalkarmsenabled.py robotIP (optional default: 127.0.0.1)"
    else:
        robotIp = sys.argv[1]

    main(robotIp)