Joint control API

NAOqi Motion - Overview | API | Tutorial


Methods

void ALMotionProxy::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.

Parameters:
  • names – Name or names of joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • 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.

almotion_angleinterpolation.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_angleinterpolation robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Setting head stiffness on.
  motion.setStiffnesses("Head", 1.0f);

  // Example showing a single target angle for one joint
  // Interpolates the head yaw to 1.0 radian in 1.0 second
  AL::ALValue names      = "HeadYaw";
  AL::ALValue angleLists = 1.0f;
  AL::ALValue timeLists  = 1.0f;
  bool isAbsolute        = true;
  std::cout << "Step 1: single target angle for one joint" << std::endl;
  motion.angleInterpolation(names, angleLists, timeLists, isAbsolute);

  qi::os::sleep(1.0f);

  // Example showing a single trajectory for one joint
  // Interpolates the head yaw to 1.0 radian and back to zero in 2.0 seconds
  names      = "HeadYaw";
  angleLists.clear();
  angleLists = AL::ALValue::array(1.0f, 0.0f);
  timeLists.clear();
  timeLists  = AL::ALValue::array(1.0f, 2.0f);
  isAbsolute = true;
  std::cout << "Step 2: single trajectory for one joint" << std::endl;
  motion.angleInterpolation(names, angleLists, timeLists, isAbsolute);

  qi::os::sleep(1.0f);

  // Example showing multiple trajectories
  // Interpolates the HeadYaw to 1.0 radian and back to zero in 2.0 seconds
  // while interpolating HeadPitch up and down over a longer period.
  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.
  angleLists.clear();
  angleLists.arraySetSize(2);
  angleLists[0] = AL::ALValue::array(1.0f, 0.0f);
  angleLists[1] = AL::ALValue::array(-0.5f, 0.5f, 0.0f);

  timeLists.clear();
  timeLists.arraySetSize(2);
  timeLists[0] = AL::ALValue::array(1.0f, 2.0f);
  timeLists[1] = AL::ALValue::array(1.0f, 2.0f, 3.0f);

  isAbsolute = true;
  std::cout << "Step 3: multiple trajectories" << std::endl;
  motion.angleInterpolation(names, angleLists, timeLists, isAbsolute);

  // Setting head stiffness off.
  motion.setStiffnesses("Head", 0.0f);

  return 0;
}

almotion_angleInterpolation.py

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

import almath
import time
import argparse
from naoqi import ALProxy

def main(robotIP, PORT = 9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

    motionProxy.setStiffnesses("Head", 1.0)

    # Example showing a single target angle for one joint
    # Interpolates the head yaw to 1.0 radian in 1.0 second
    names      = "HeadYaw"
    angleLists = 50.0*almath.TO_RAD
    timeLists  = 1.0
    isAbsolute = True
    motionProxy.angleInterpolation(names, angleLists, timeLists, isAbsolute)

    time.sleep(1.0)

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

    time.sleep(1.0)

    # Example showing multiple trajectories
    names      = ["HeadYaw", "HeadPitch"]
    angleLists = [30.0*almath.TO_RAD, 30.0*almath.TO_RAD]
    timeLists  = [1.0, 1.2]
    isAbsolute = True
    motionProxy.angleInterpolation(names, angleLists, timeLists, isAbsolute)

    # Example showing multiple trajectories
    # Interpolates 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  = [[50.0*almath.TO_RAD, 0.0],
                   [-30.0*almath.TO_RAD, 30.0*almath.TO_RAD, 0.0]]
    timeLists   = [[1.0, 2.0], [ 1.0, 2.0, 3.0]]
    isAbsolute  = True
    motionProxy.angleInterpolation(names, angleLists, timeLists, isAbsolute)

    motionProxy.setStiffnesses("Head", 0.0)


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::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.

Parameters:
  • names – Name or names of joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • targetAngles – An angle, or list of angles in radians
  • maxSpeedFraction – A fraction.

almotion_angleinterpolationwithspeed.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_angleinterpolationwithspeed robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Setting head stiffness on.
  motion.setStiffnesses("Head", 1.0f);

  // 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
  std::cout << "Step 1: single target for one joint." << std::endl;
  motion.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction);

  qi::os::sleep(1.0f);

  // 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 = AL::ALValue::array(0.5f, 0.25f);
  maxSpeedFraction  = 0.2f; // Using 20% of maximum joint speed
  std::cout << "Step 2: multiple joints." << std::endl;
  motion.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction);

  // Setting head stiffness off.
  motion.setStiffnesses("Head", 0.0f);

  return 0;
}

almotion_angleInterpolationWithSpeed.py

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

import time
import argparse
from naoqi import ALProxy

def main(robotIP, PORT = 9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)
    postureProxy = ALProxy("ALRobotPosture", robotIP, PORT)

    # Wake up robot
    motionProxy.wakeUp()

    # Send robot to Stand Init
    postureProxy.goToPosture("StandInit", 0.5)

    # 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
    motionProxy.angleInterpolation(names, angleLists, timeLists, isAbsolute)

    time.sleep(1.0)

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

    time.sleep(1.0)

    # 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
    motionProxy.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction)

    # 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 getBodyNames 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(motionProxy.getBodyNames("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
    motionProxy.angleInterpolationWithSpeed(names, targetAngles, maxSpeedFraction)

    # Go to rest position
    motionProxy.rest()

if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::angleInterpolationBezier(const std::vector<std::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.

Parameters:
  • jointNames – A vector of joint names, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • times – A ragged ALValue matrix of floats. Each line corresponding to a motor, and column element to a control point.
  • controlPoints – A list of angles in radians or an ALValue array of arrays each containing [float angle, Handle1, Handle2], where Handle is [int InterpolationType, float dTime, float dAngle] describing the handle offsets relative to the angle and time of the point. The first Bezier param describes the handle that controls the curve preceding the point, the second describes the curve following the point.

almotion_angleinterpolationbezier.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_angleinterpolationBezier robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Setting head stiffness on.
  motion.setStiffnesses("Head", 1.0f);

  // Example showing a single target angle for one joint
  // Interpolates the head yaw to 1.0 radian in 1.0 second
  std::vector<std::string> names;
  AL::ALValue timeLists;
  AL::ALValue angleLists;

  names.push_back("HeadYaw");
  timeLists.arrayPush(AL::ALValue::array(1.0f));
  angleLists.arrayPush(AL::ALValue::array(1.0f));

  std::cout << "Step 1: single target angle for one joint" << std::endl;
  motion.angleInterpolationBezier(names, timeLists, angleLists);

  qi::os::sleep(1.0f);

  // Example showing a single trajectory for one joint
  // Interpolates the head yaw to 1.0 radian and back to zero in 2.0 seconds
  timeLists.clear();
  timeLists.arrayPush(AL::ALValue::array(1.0f, 2.0f));

  angleLists.clear();
  angleLists.arrayPush(AL::ALValue::array(1.0f, 0.0f));
  std::cout << "Step 2: single trajectory for one joint" << std::endl;
  motion.angleInterpolationBezier(names, timeLists, angleLists);

  qi::os::sleep(1.0f);

  // Example showing multiple trajectories
  // Interpolates the HeadYaw to 1.0 radian and back to zero in 2.0 seconds
  // while interpolating HeadPitch up and down over a longer period.
  names.at(0) = "Head";
  // 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.
  timeLists.clear();
  timeLists.arraySetSize(2);
  timeLists[0] = AL::ALValue::array(1.0f, 2.0f);
  timeLists[1] = AL::ALValue::array(1.0f, 2.0f, 3.0f);

  angleLists.clear();
  angleLists.arraySetSize(2);
  angleLists[0] = AL::ALValue::array(1.0f, 0.0f);
  angleLists[1] = AL::ALValue::array(-0.5f, 0.5f, 0.0f);
  std::cout << "Step 3: multiple trajectories" << std::endl;
  motion.angleInterpolationBezier(names, timeLists, angleLists);

  // Setting head stiffness off.
  motion.setStiffnesses("Head", 0.0f);

  return 0;
}

almotion_angleInterpolationBezier.py

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

import almath
import time
import argparse
from naoqi import ALProxy

def main(robotIP, PORT = 9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

    motionProxy.setStiffnesses("Head", 1.0)

    # Example showing a single target angle for one joint
    # Interpolates the head yaw to 1.0 radian in 1.0 second
    names      = ["HeadYaw"]
    angleLists = [[50.0*almath.TO_RAD]]
    timeLists  = [[1.0]]
    motionProxy.angleInterpolationBezier(names, timeLists, angleLists)

    time.sleep(1.0)

    # Example showing a single trajectory for one joint
    # Interpolates the head yaw to 1.0 radian and back to zero in 2.0 seconds
    names      = ["HeadYaw"]
    #              2 angles
    angleLists = [[30.0*almath.TO_RAD, 0.0]]
    #              2 times
    timeLists  = [[1.0, 2.0]]
    motionProxy.angleInterpolationBezier(names, timeLists, angleLists)

    time.sleep(1.0)

    # Example showing multiple trajectories
    names      = ["HeadYaw", "HeadPitch"]
    angleLists = [[30.0*almath.TO_RAD], [30.0*almath.TO_RAD]]
    timeLists  = [[1.0], [1.2]]
    motionProxy.angleInterpolationBezier(names, timeLists, angleLists)

    # Example showing multiple trajectories
    # Interpolates 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  = ["Head"]
    # 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  = [[50.0*almath.TO_RAD, 0.0],
                   [-30.0*almath.TO_RAD, 30.0*almath.TO_RAD, 0.0]]
    timeLists   = [[1.0, 2.0], [ 1.0, 2.0, 3.0]]
    motionProxy.angleInterpolationBezier(names, timeLists, angleLists)

    motionProxy.setStiffnesses("Head", 0.0)


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::setAngles(const AL::ALValue& names, const AL::ALValue& angles, const float& fractionMaxSpeed)

Sets angles. This is a non-blocking call.

Parameters:
  • names – The name or names of joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • angles – One or more angles in radians
  • fractionMaxSpeed – The fraction of maximum speed to use

almotion_setangles.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_setangles robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // 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.3f, -0.3f);
  float fractionMaxSpeed  = 0.1f;
  motion.setStiffnesses(names, AL::ALValue::array(1.0f, 1.0f));
  qi::os::sleep(1.0f);
  motion.setAngles(names, angles, fractionMaxSpeed);
  qi::os::sleep(1.0f);
  motion.setStiffnesses(names, AL::ALValue::array(0.0f, 0.0f));

  return 0;
}

almotion_setAngles.py

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

import time
import argparse
from naoqi import ALProxy

def main(robotIP, PORT=9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

    motionProxy.setStiffnesses("Head", 1.0)

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

    time.sleep(3.0)
    motionProxy.setStiffnesses("Head", 0.0)


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::changeAngles(const AL::ALValue& names, const AL::ALValue& changes, const float& fractionMaxSpeed)

Changes Angles. This is a non-blocking call.

Parameters:
  • names – The name or names of joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • changes – One or more changes in radians
  • fractionMaxSpeed – The fraction of maximum speed to use

almotion_changeangles.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_changeangles robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Setting head stiffness on.
  motion.setStiffnesses("Head", 1.0f);

  // 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;
  motion.changeAngles(names, changes, fractionMaxSpeed);

  qi::os::sleep(1.0f);

  // Setting head stiffness off.
  motion.setStiffnesses("Head", 0.0f);

  return 0;
}

almotion_changeAngles.py

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

import time
import argparse
from naoqi import ALProxy

def main(robotIP, PORT = 9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

    motionProxy.setStiffnesses("Head", 1.0)

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

    time.sleep(2.0)

    motionProxy.setStiffnesses("Head", 0.0)


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
std::vector<float> ALMotionProxy::getAngles(const AL::ALValue& names, const bool& useSensors)

Gets the angles of the joints

Parameters:
  • names – Names the joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”.
  • useSensors – If true, sensor angles will be returned
Returns:

Joint angles in radians.

almotion_getangles.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_getangles robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example that finds the difference between the command and sensed angles.
  std::string names = "Body";
  bool useSensors   = false;
  std::vector<float> commandAngles = motion.getAngles(names, useSensors);
  std::cout << "Command angles: " << std::endl << commandAngles << std::endl;
  useSensors = true;
  std::vector<float> sensorAngles = motion.getAngles(names, useSensors);
  std::cout << "Sensor angles: " << std::endl << sensorAngles << std::endl;

  return 0;
}

almotion_getAngles.py

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

import argparse
from naoqi import ALProxy

def main(robotIP, PORT=9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

    # Example that finds the difference between the command and sensed angles.
    names         = "Body"
    useSensors    = False
    commandAngles = motionProxy.getAngles(names, useSensors)
    print "Command angles:"
    print str(commandAngles)
    print ""

    useSensors  = True
    sensorAngles = motionProxy.getAngles(names, useSensors)
    print "Sensor angles:"
    print str(sensorAngles)
    print ""

    errors = []
    for i in range(0, len(commandAngles)):
        errors.append(commandAngles[i]-sensorAngles[i])
    print "Errors"
    print errors


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::closeHand(const std::string& handName)

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

Parameters:
  • handName – The name of the hand. Could be: “RHand” or “LHand”

almotion_closehand.cpp

#include <iostream>
#include <alproxies/almotionproxy.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_closehand robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example showing how to close the right hand.
  const std::string handName = "RHand";
  motion.closeHand(handName);

  return 0;
}

almotion_closeHand.py

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

import argparse
from naoqi import ALProxy

def main(robotIP, PORT=9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

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

if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)
void ALMotionProxy::openHand(const std::string& handName)

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

Parameters:
  • handName – The name of the hand. Could be: “RHand or “LHand”

almotion_openhand.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_openhand robotIp "
              << "(optional default \"127.0.0.1\")."<< std::endl;
  }
  else {
    robotIp = argv[1];
  }

  AL::ALMotionProxy motion(robotIp);

  // Example showing how to open the right hand.
  std::string handName = "RHand";
  motion.openHand(handName);

  return 0;
}

almotion_openHand.py

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

import argparse
from naoqi import ALProxy

def main(robotIP, PORT=9559):
    motionProxy = ALProxy("ALMotion", robotIP, PORT)

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


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot ip address")
    parser.add_argument("--port", type=int, default=9559,
                        help="Robot port number")

    args = parser.parse_args()
    main(args.ip, args.port)