.. _control-cartesian-api: Cartesian control API +++++++++++++++++++++ :ref:`Overview ` | API | :ref:`Tutorial ` .. seealso:: - :ref:`naoqi-motion` ------------ Method list ----------- .. cpp:class:: ALMotionProxy * :cpp:func:`ALMotionProxy::positionInterpolation` * :cpp:func:`ALMotionProxy::positionInterpolations` * :cpp:func:`ALMotionProxy::setPosition` * :cpp:func:`ALMotionProxy::changePosition` * :cpp:func:`ALMotionProxy::getPosition` * :cpp:func:`ALMotionProxy::transformInterpolation` * :cpp:func:`ALMotionProxy::transformInterpolations` * :cpp:func:`ALMotionProxy::setTransform` * :cpp:func:`ALMotionProxy::changeTransform` * :cpp:func:`ALMotionProxy::getTransform` .. cpp:function:: void ALMotionProxy::positionInterpolation( const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& durations, const bool& isAbsolute ) Moves an end-effector to the given position and orientation over time. This is a blocking call. :param chainName: Name of the chain. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param path: Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :param durations: Vector of times in seconds corresponding to the path points :param isAbsolute: If true, the movement is absolute else relative :download:`almotion_positioninterpolation.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_positioninterpolation.cpp :language: cpp :download:`almotion_positioninterpolation.py ` .. literalinclude:: /samples/python/almotion/almotion_positioninterpolation.py :language: py .. cpp:function:: void ALMotionProxy::positionInterpolations( const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute ) Moves end-effectors to the given positions and orientations over time. This is a blocking call. :param effectorNames: Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" :param taskSpaceForAllPaths: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param paths: Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians :param axisMasks: Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :param relativeTimes: Vector of times in seconds corresponding to the path points :param isAbsolute: If true, the movement is absolute else relative :download:`almotion_positioninterpolations.py ` .. literalinclude:: /samples/python/almotion/almotion_positioninterpolations.py :language: py .. cpp:function:: void ALMotionProxy::setPosition( const std::string& chainName, const int& space, const std::vector& position, const float& fractionMaxSpeed, const int& axisMask ) Moves an end-effector to the given position and orientation. This is a non-blocking call. :param chainName: Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param position: 6D position array (x,y,z,wx,wy,wz) in meters and radians :param fractionMaxSpeed: The fraction of maximum speed to use :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :download:`almotion_setposition.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_setposition.cpp :language: cpp :download:`almotion_setposition.py ` .. literalinclude:: /samples/python/almotion/almotion_setposition.py :language: py .. cpp:function:: void ALMotionProxy::changePosition( const std::string& effectorName, const int& space, const std::vector& positionChange, const float& fractionMaxSpeed, const int& axisMask ) Creates a move of an end effector in cartesian space. This is a non-blocking call. :param effectorName: Name of the effector. :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param positionChange: 6D position change array (xd, yd, zd, wxd, wyd, wzd) in meters and radians :param fractionMaxSpeed: The fraction of maximum speed to use :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :download:`almotion_changeposition.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_changeposition.cpp :language: cpp :download:`almotion_changeposition.py ` .. literalinclude:: /samples/python/almotion/almotion_changeposition.py :language: py .. cpp:function:: std::vector ALMotionProxy::getPosition( const std::string& name, const int& space, const bool& useSensorValues ) Gets a Position relative to the TASK_SPACE. Axis definition: the x axis is positive toward NAO's front, the y from right to left and the z is vertical. The angle convention of Position6D is Rot_z(wz).Rot_y(wy).Rot_x(wx). :param name: Name of the item. Could be: Head, LArm, RArm, LLeg, RLeg, Torso, CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4. Use getSensorNames for the list of sensors supported on your robot. :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param useSensorValues: If true, the sensor values will be used to determine the position. :return: Vector containing the Position6D using meters and radians (x, y, z, wx, wy, wz) :download:`almotion_getposition.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_getposition.cpp :language: cpp :download:`almotion_getposition.py ` .. literalinclude:: /samples/python/almotion/almotion_getposition.py :language: py .. cpp:function:: void ALMotionProxy::transformInterpolation( const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& duration, const bool& isAbsolute ) Moves an end-effector to the given position and orientation over time using homogenous transforms to describe the positions or changes. This is a blocking call. :param chainName: Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param path: Vector of Transform arrays :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :param duration: Vector of times in seconds corresponding to the path points :param isAbsolute: If true, the movement is absolute else relative :download:`almotion_transforminterpolation.py ` .. literalinclude:: /samples/python/almotion/almotion_transforminterpolation.py :language: py .. cpp:function:: void ALMotionProxy::transformInterpolations( const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute ) Moves end-effector to the given transforms over time. This is a blocking call. :param effectorNames: Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" :param taskSpaceForAllPaths: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param paths: Vector of transforms arrays. :param axisMasks: Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :param relativeTimes: Vector of times in seconds corresponding to the path points :param isAbsolute: If true, the movement is absolute else relative :download:`almotion_transforminterpolations.py ` .. literalinclude:: /samples/python/almotion/almotion_transforminterpolations.py :language: py .. cpp:function:: void ALMotionProxy::setTransform( const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask ) Moves an end-effector to the given position and orientation transform. This is a non-blocking call. :param chainName: Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param transform: Transform arrays :param fractionMaxSpeed: The fraction of maximum speed to use :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :download:`almotion_settransform.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_settransform.cpp :language: cpp :download:`almotion_settransform.py ` .. literalinclude:: /samples/python/almotion/almotion_settransform.py :language: py .. cpp:function:: void ALMotionProxy::changeTransform( const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask ) Moves an end-effector to the given position and orientation transform. This is a non-blocking call. :param chainName: Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param transform: Transform arrays :param fractionMaxSpeed: The fraction of maximum speed to use :param axisMask: Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both :download:`almotion_changetransform.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_changetransform.cpp :language: cpp :download:`almotion_changetransform.py ` .. literalinclude:: /samples/python/almotion/almotion_changetransform.py :language: py .. cpp:function:: std::vector ALMotionProxy::getTransform( const std::string& name, const int& space, const bool& useSensorValues ) Gets an Homogenous Transform relative to the TASK_SPACE. Axis definition: the x axis is positive toward NAO's front, the y from right to left and the z is vertical. :param name: Name of the item. Could be: any joint or chain or sensor (Head, LArm, RArm, LLeg, RLeg, Torso, HeadYaw, ..., CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4. Use getSensorNames for the list of sensors supported on your robot. :param space: Task space {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. :param useSensorValues: If true, the sensor values will be used to determine the position. :return: Vector of 16 floats corresponding to the values of the matrix, line by line. :download:`almotion_gettransform.cpp ` .. literalinclude:: /samples/cpp/almotion/almotion_gettransform.cpp :language: cpp :download:`almotion_gettransform.py ` .. literalinclude:: /samples/python/almotion/almotion_gettransform.py :language: py