Ptu46

class Ptu46(self)

Bases: pybind11_object

Jacobian, geometric model functionalities… for ptu46, pan, tilt head from Directed Perception.

See http://www.DPerception.com for more details.

Default constructor. Call init() .

Methods

__init__

Default constructor.

computeMGD

Overloaded function.

get_cMe

Get the homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame.

get_cVe

Get the twist matrix corresponding to the transformation between the camera frame and the end effector frame.

get_eJe

Get the robot jacobian expressed in the end-effector frame.

get_fJe

Get the robot jacobian expressed in the robot reference frame

init

Initialization.

Inherited Methods

Operators

__doc__

__init__

Default constructor.

__module__

__repr__

Attributes

L

__annotations__

h

ndof

__init__(self)

Default constructor. Call init() .

computeMGD(*args, **kwargs)

Overloaded function.

  1. computeMGD(self: visp._visp.robot.Ptu46, q: visp._visp.core.ColVector, fMc: visp._visp.core.HomogeneousMatrix) -> None

Compute the direct geometric model of the camera: fMc

Parameters:
q

Articular position for pan and tilt axis.

fMc

Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame.

  1. computeMGD(self: visp._visp.robot.Ptu46, q: visp._visp.core.ColVector) -> visp._visp.core.HomogeneousMatrix

Return the direct geometric model of the camera: fMc

Parameters:
q

Articular position for pan and tilt axis.

Returns:

fMc, the homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame.

  1. computeMGD(self: visp._visp.robot.Ptu46, q: visp._visp.core.ColVector, r: visp._visp.core.PoseVector) -> None

Compute the direct geometric model of the camera in terms of pose vector.

Parameters:
q

Articular position for pan and tilt axis.

r

Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame.

get_cMe(self, _cMe: visp._visp.core.HomogeneousMatrix) None

Get the homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.

get_cVe(self, _cVe: visp._visp.core.VelocityTwistMatrix) None

Get the twist matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.

get_eJe(self, q: visp._visp.core.ColVector, eJe: visp._visp.core.Matrix) None

Get the robot jacobian expressed in the end-effector frame.

Warning

Re is not the embedded camera frame. It corresponds to the frame associated to the tilt axis (see also get_cMe).

Parameters:
q: visp._visp.core.ColVector

Articular position for pan and tilt axis.

eJe: visp._visp.core.Matrix

Jacobian between end effector frame and end effector frame (on tilt axis).

get_fJe(self, q: visp._visp.core.ColVector, fJe: visp._visp.core.Matrix) None

Get the robot jacobian expressed in the robot reference frame

Parameters:
q: visp._visp.core.ColVector

Articular position for pan and tilt axis.

fJe: visp._visp.core.Matrix

Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

init(self) None

Initialization. Here nothing to do.