NAOqi Motion - Overview | API | robot position Tutorial
Deprecated Methods
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: |
|
---|
Makes the robot move at the given velocity, expressed in FRAME_ROBOT, with a move configuration. This is a non-blocking call.
Parameters: |
|
---|
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: |
|
---|
Makes the robot move at the given normalized velocity, expressed in FRAME_ROBOT, with a move configuration. This is a non-blocking call.
Parameters: |
|
---|
# -*- 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 Pose Init
postureProxy.goToPosture("StandInit", 0.5)
# Example showing the use of moveToward
# 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.moveToward(x, y, theta, [["Frequency", 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.moveToward(x, y, theta, [["Frequency", frequency]])
# Lets make him slow down(frequency) after 3 seconds
time.sleep(3)
frequency = 0.5
motionProxy.moveToward(x, y, theta, [["Frequency", 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
# 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)
Deprecated since version 1.22: use ALMotionProxy::moveToward() instead. Note that ‘frequency’ parameter is now set using ‘MaxStepFrequency’ inside Move config parameter.
NAO only
There are three overloads of this function:
Makes the robot walk at the given velocity. This is a non-blocking call.
Parameters: |
|
---|
Deprecated since version 1.22: use ALMotionProxy::moveToward() instead. Note that ‘frequency’ parameter is now set using ‘MaxStepFrequency’ inside Move config parameter.
NAO only
Makes the robot walk at the given velocity. This is a non-blocking call.
Parameters: |
|
---|
Deprecated since version 1.22: use ALMotionProxy::moveToward() instead. Note that ‘frequency’ parameter is now set using ‘MaxStepFrequency’ inside Move config parameter.
NAO only
Makes the robot walk at the given velocity. This is a non-blocking call.
Parameters: |
|
---|
There are four overloads of this function:
Makes the robot move to the given pose in the ground plane, relative to FRAME_ROBOT. This is a blocking call.
Parameters: |
|
---|
#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;
}
# -*- encoding: UTF-8 -*-
import math
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 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.
# 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)
Makes the robot move to the given pose in the ground plane, relative to FRAME_ROBOT, with custom move configuration. This is a blocking call.
Parameters: |
|
---|
Makes the robot move to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points. This is a blocking call.
Parameters: |
|
---|
Makes the robot 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: |
|
---|
Pepper only
Makes the robot move to the relative position (x, y, theta) in pTime.
If pTime is too short, the robot will move to (x, y, theta) in optimal time (> pTime), and NAOqi will warn the user that input time is not achievable.
Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.
Makes the robot walk to the given pose in the ground plane, relative to FRAME_ROBOT. This is a blocking call.
Parameters: |
|
---|
Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.
Makes the robot move to the given pose in the ground plane, relative to FRAME_ROBOT, with custom gait parameters. This is a blocking call.
Parameters: |
|
---|
Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.
Makes the robot move to the given pose in the ground plane, relative to FRAME_ROBOT, while passing through check points. This is a blocking call.
Parameters: |
|
---|
Deprecated since version 1.14: use ALMotionProxy::moveTo() instead.
Makes the robot 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: |
|
---|
NAO only
Makes the robot do foot step planner. This is a non-blocking call.
Parameters: |
|
---|
# -*- 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 Pose Init
postureProxy.goToPosture("StandInit", 0.5)
# A small step forwards and anti-clockwise with the left foot
legName = ["LLeg"]
X = 0.04
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.04
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)
motionProxy.waitUntilMoveIsFinished()
# 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)
NAO only
Makes the robot do foot step planner with speed. This is a blocking call.
Parameters: |
|
---|
almotion_setFootStepsWithSpeed.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 Pose Init
postureProxy.goToPosture("StandInit", 0.5)
# A small step forwards and anti-clockwise with the left foot
legName = ["LLeg"]
X = 0.04
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.04
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)
motionProxy.waitUntilMoveIsFinished()
# 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)
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.
# -*- 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 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 ""
motionProxy.waitUntilMoveIsFinished()
# 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)
Deprecated since version 1.14: use ALMotionProxy::moveInit() instead.
Initializes the move process. Checks the robot pose and takes a right posture. This is blocking called.
#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;
}
# -*- encoding: UTF-8 -*-
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 Pose Init
postureProxy.goToPosture("StandInit", 0.5)
# Example showing how Initialize move process.
motionProxy.moveInit()
# 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)
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.
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 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 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"
# 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)
Returns: | True if Walk is Active. |
---|
Deprecated since version 1.14: use ALMotionProxy::moveIsActive() instead.
Returns: | True if move is Active. |
---|
#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;
}
# -*- 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 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
# 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)
Stops Walk task at next double support: this method will end the walk task less brutally than killWalk but more quickly than move(0.0, 0.0, 0.0).
Deprecated since version 1.14: use ALMotionProxy::stopMove() instead.
Stops Move task at next double support: this method will end the move task less brutally than killMove but more quickly than move(0.0, 0.0, 0.0).
Gets the foot Gait config (“MaxStepX”, “MaxStepY”, “MaxStepTheta”, “MaxStepFrequency”, “StepHeight”, “TorsoWx”, “TorsoWy”).
Deprecated since version 1.14: use ALMotionProxy::getMoveConfig() instead.
Parameters: |
|
---|---|
Returns: | An ALValue with the following form [ ["MaxStepX", value],
["MaxStepY", value],
["MaxStepTheta", value],
["MaxStepFrequency", value],
["StepHeight", value],
["TorsoWx", value],
["TorsoWy", value]
]
|
Gets the move config (“MaxStepX”, “MaxStepY”, “MaxStepTheta”, “MaxStepFrequency”, “StepHeight”, “TorsoWx”, “TorsoWy”).
Parameters: |
|
---|---|
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 extreme values and could create
# some strange walk behavior
import time
proxy.moveInit()
proxy.moveToward(1.0, 0.0, 0.0, proxy.getMoveConfig("Min"))
time.sleep(3.0)
proxy.stopMove()
Gets the World Absolute Robot Position.
Parameters: |
|
---|---|
Returns: | A vector containing the World Absolute Robot Position. (Absolute Position X in meter, Absolute Position Y in meter, Absolute Angle Theta (Wz) in radian). Wz is an angle between ]-pi, pi]. |
#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;
}
# -*- encoding: UTF-8 -*-
import almath
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 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
# 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)
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 in meter, Absolute Position Y in meter, Absolute Angle Theta (Wz) in radian). Wz is an angle between ]-pi, pi]. |
---|
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 almath
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 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 = almath.Pose2D(motionProxy.getNextRobotPosition())
# Make the robot move
motionProxy.moveTo(0.1, 0.0, 0.2)
endRobotPosition = almath.Pose2D(motionProxy.getNextRobotPosition())
# Compute robot's' displacement
robotMove = almath.pose2DInverse(initRobotPosition)*endRobotPosition
print "Robot Move :", robotMove
# 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)
Gets the Absolute Robot Velocity, expressed in FRAME_ROBOT.
Returns: | A vector containing the Absolute Robot Velocity. (Absolute Velocity Translation X [m.s-1], Absolute Velocity Translation Y[m.s-1], Absolute Velocity Rotation WZ [rd.s-1]) |
---|
#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 absolute robot velocity in FRAME_ROBOT.
std::vector<float> result = motion.getRobotVelocity();
std::cout << "Robot velocity is: " << result << std::endl;
return 0;
}
# -*- encoding: UTF-8 -*-
import argparse
from naoqi import ALProxy
def main(robotIP, PORT=9559):
motionProxy = ALProxy("ALMotion", robotIP, PORT)
# Example showing how to get a simplified absolute robot velocity in FRAME_ROBOT.
result = motionProxy.getRobotVelocity()
print "Robot Velocity: ", result
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)
Deprecated since version 1.22: use ALMotionProxy::getMoveArmsEnabled() instead.
Gets if Arms Motions are enabled during the Walk Process.
Returns: | True Arm Motions are controlled by the Walk Task. |
---|
Deprecated since version 1.22: use ALMotionProxy::setMoveArmsEnabled() instead.
Sets if Arms Motions are enabled during the Walk Process.
Parameters: |
|
---|
Gets if Arms Motions are enabled during the Move Process.
Parameters: |
|
---|---|
Returns: | For “LArm” and “RArm”, returns true if the corresponding arm is enabled. For “Arms”, returns true if both arms are enabled. Returns false otherwise. |
almotion_getMoveArmsEnabled.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_getMoveArmsEnable 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
std::cout << "LeftArmEnabled: " << motion.getMoveArmsEnabled("LArm") << std::endl;
std::cout << "RightArmEnabled: " << motion.getMoveArmsEnabled("RArm") << std::endl;
std::cout << "BothArmsEnabled: " << motion.getMoveArmsEnabled("Arms") << std::endl;
return 0;
}
# -*- encoding: UTF-8 -*-
import argparse
from naoqi import ALProxy
def main(robotIP, PORT=9559):
motionProxy = ALProxy("ALMotion", robotIP, PORT)
# Example showing how to get the enabled flags for the arms
print 'LeftArmEnabled: ', motionProxy.getMoveArmsEnabled("LArm")
print 'RightArmEnabled: ', motionProxy.getMoveArmsEnabled("RArm")
print 'BothArmsEnabled: ', motionProxy.getMoveArmsEnabled("Arms")
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)
Sets if Arms Motions are enabled during the Move Process.
Parameters: |
|
---|
almotion_setMoveArmsEnabled.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 Pose Init
postureProxy.goToPosture("StandInit", 0.5)
x = 0.6
y = 0.0
theta = 0.0
frequency = 1.0
motionProxy.moveToward(x, y, theta, [["Frequency", frequency]])
time.sleep(2.0)
# Example showing how to disable left arm motions during a move
leftArmEnable = False
rightArmEnable = True
motionProxy.setMoveArmsEnabled(leftArmEnable, rightArmEnable)
print "Disabled left arm"
# disable also right arm motion after 1 seconds
time.sleep(1.0)
rightArmEnable = False
motionProxy.setMoveArmsEnabled(leftArmEnable, rightArmEnable)
print "Disabled right arm"
time.sleep(1.0)
motionProxy.stopMove()
leftArmEnable = True
rightArmEnable = True
motionProxy.setMoveArmsEnabled(leftArmEnable, rightArmEnable)
# 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)