SoftBank Robotics documentation What's new in NAOqi 2.5?

Stiffness control

NAOqi Motion - Overview | API


What it does

These API control the Stiffness of one or several joint(s).
The Stiffness of the joint is equivalent to a torque limitation into the motors.
  • If the joint stiffness is set to 0.0, the joint controller does nothing and the joint is free.
  • Else with a value at 1.0 the joint is allowed to use full torque power to reach a given position.
  • Between these two extremes, the joint is more or less compliant (tries to reach a position but if torque need to move is higher than the limitation of Stiffness, the joint doesn’t reach the target position).
The Stiffness can be managed:
A robot is considered awake when it can stand and move around, that is, when its leg joints are stiffnessed. The robotIsWakeUp() event is raised when the awake status of the robot changes.

How it works

These API just create a higher level of the DCM hardness definition and provide interpolation in order to have more smooth behavior.

Performances and limitations

pepp Pepper only

Manual Stiffness control is forbidden for Pepper‘s lower part.

With the following methods:

You could only use:

  • “Head”, “LArm” and “RArm”
  • “LHand” and “RHand”

Workaround:

use ALMotionProxy::wakeUp and ALMotionProxy::rest methods.

Use Cases

Case 1: Stiffness On

When the robot is switched on, he initially has zero Stiffness. When at zero Stiffness, you can send any commands to the motors, but he will not move.

To give power to the motors, you can call one of Motion’s Stiffness methods:

almotion_stiffnessOn.py

#! /usr/bin/env python
# -*- encoding: UTF-8 -*-

"""Example: Stiffness On - Active Stiffness of All Joints and Actuators"""

import qi
import argparse
import sys
import time


def main(session):
    """
    Stiffness On - Active Stiffness of All Joints and Actuators.
    This example is only compatible with NAO.
    """
    # Get the services ALMotion & ALRobotPosture.

    motion_service = session.service("ALMotion")

    # We use the "Body" name to signify the collection of all joints
    names = "Body"
    stiffnessLists = 1.0
    timeLists = 1.0
    motion_service.stiffnessInterpolation(names, stiffnessLists, timeLists)

    # print motion state
    print motion_service.getSummary()

    time.sleep(2.0)

    # Go to rest position
    motion_service.rest()


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot IP address. On robot or Local Naoqi: use '127.0.0.1'.")
    parser.add_argument("--port", type=int, default=9559,
                        help="Naoqi port number")

    args = parser.parse_args()
    session = qi.Session()
    try:
        session.connect("tcp://" + args.ip + ":" + str(args.port))
    except RuntimeError:
        print ("Can't connect to Naoqi at ip \"" + args.ip + "\" on port " + str(args.port) +".\n"
               "Please check your script arguments. Run with -h option for help.")
        sys.exit(1)
    main(session)

Avoiding judder

When changing Stiffness away from zero, it is best to do it gently so as to reduce the chance of a judder when powering up the motors.

Adapting the Stiffness to task

Many tasks can be achieved at less than maximum Stiffness (Stiffness = 0.6), but tasks such as “Get up” require all the power they can get (Stiffness = 1.0).

Case 2: Stiffness Off

When you reduce the Stiffness to zero, you cut all the power to the motors, so you should be careful that the robot is in a self-stable pose, otherwise he could fall.

almotion_stiffnessOff.py

#! /usr/bin/env python
# -*- encoding: UTF-8 -*-

"""Example : Stiffness Off - remove stiffness of all joints and actuators"""

import qi
import argparse
import sys


def main(session):
    """
    Stiffness Off - remove stiffness of all joints and actuators.
    This example is only compatible with NAO.
    """
    # Get the service ALMotion.

    motion_service = session.service("ALMotion")

    # We use the "Body" name to signify the collection of all joints
    names = "Body"
    stiffnessLists = 0.0
    timeLists = 1.0
    motion_service.stiffnessInterpolation(names, stiffnessLists, timeLists)

    # print motion state
    print motion_service.getSummary()


if __name__ == "__main__":
    parser = argparse.ArgumentParser()
    parser.add_argument("--ip", type=str, default="127.0.0.1",
                        help="Robot IP address. On robot or Local Naoqi: use '127.0.0.1'.")
    parser.add_argument("--port", type=int, default=9559,
                        help="Naoqi port number")

    args = parser.parse_args()
    session = qi.Session()
    try:
        session.connect("tcp://" + args.ip + ":" + str(args.port))
    except RuntimeError:
        print ("Can't connect to Naoqi at ip \"" + args.ip + "\" on port " + str(args.port) +".\n"
               "Please check your script arguments. Run with -h option for help.")
        sys.exit(1)
    main(session)

Case 3: Stiffness Trajectories

Should you wish to vary the Stiffness of a joint over time, you can request a ‘trajectory’ of Stiffness.

# Example showing a stiffness trajectory
# Here the stiffness of the HeadYaw Joint, rises to
# 0.8, then goes back to zero.
pNames          = "HeadYaw"
pStiffnessLists = [0.0, 0.8, 0.0]
pTimeLists      = [0.5, 1.0, 1.5]
proxy.stiffnessInterpolation(pNames, pStiffnessLists, pTimeLists)

Like angle interpolation commands, multiple trajectories can be specified in the same command.

# Example showing multiple stiffness trajectories
# Here the stiffness of the HeadYaw Joint, rises to
# 0.5, then goes back to zero, while the HeadPitch
# joint rises to 1.0
pNames          = ["HeadYaw", "HeadPitch"]
pStiffnessLists = [[0.0, 0.5, 0.0], [0.0, 1.0, 0.0]]
pTimeLists      = [[0.5, 1.0, 1.5], [0.5, 1.0, 1.5]]
proxy.stiffnessInterpolation(pNames, pStiffnessLists, pTimeLists)