Biclops

class Biclops(self)

Bases: pybind11_object

Jacobian, geometric model functionalities… for Biclops, pan, tilt head.

Two different Denavit-Hartenberg representations of the robot are implemented. As mentioned in vpBiclops::DenavitHartenbergModel they differ in the orientation of the tilt axis. Use setDenavitHartenbergModel() to select the representation.

See http://www.traclabs.com/tracbiclops.htm for more details concerning the hardware.

Default constructor. Call init() that sets vpBiclops::DH1 Denavit-Hartenberg model.

Methods

__init__

Default constructor.

computeMGD

Overloaded function.

getDenavitHartenbergModel

Return the Denavit-Hartenberg representation used to model the head.

get_cMe

Return the transformation \({^c}{\bf M}_e\) 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

get_fMc

Overloaded function.

get_fMe

Return the direct geometric model of the end effector: fMe

init

Initialization.

setDenavitHartenbergModel

Set the Denavit-Hartenberg representation used to model the head.

set_cMe

Overloaded function.

Inherited Methods

Operators

__doc__

__init__

Default constructor.

__module__

__repr__

Attributes

DH1

DH2

__annotations__

h

ndof

panJointLimit

speedLimit

tiltJointLimit

class DenavitHartenbergModel(self, value: int)

Bases: pybind11_object

Two different Denavit-Hartenberg representations of the robot are implemented. As you can see in the next image, they differ in the orientation of the tilt axis.

<unparsed image <doxmlparser.compound.docImageType object at 0x7ff693712740>>

The first representation, vpBiclops::DH1 is given by:

<unparsed table <doxmlparser.compound.docTableType object at 0x7ff693712c20>>

The second one, vpBiclops::DH2 is given by:

<unparsed table <doxmlparser.compound.docTableType object at 0x7ff693740430>>

where \(q_1, q_2\) are respectively the pan and tilt joint positions.

In those representations, the pan is oriented from left to right, while the tilt is oriented

  • in vpBiclops::DH1 from down to top,

  • in vpBiclops::DH2 from top to down.

Values:

  • DH1: First Denavit-Hartenberg representation.

  • DH2: Second Denavit-Hartenberg representation.

__and__(self, other: object) object
__eq__(self, other: object) bool
__ge__(self, other: object) bool
__getstate__(self) int
__gt__(self, other: object) bool
__hash__(self) int
__index__(self) int
__init__(self, value: int)
__int__(self) int
__invert__(self) object
__le__(self, other: object) bool
__lt__(self, other: object) bool
__ne__(self, other: object) bool
__or__(self, other: object) object
__rand__(self, other: object) object
__ror__(self, other: object) object
__rxor__(self, other: object) object
__setstate__(self, state: int) None
__xor__(self, other: object) object
property name : str
__init__(self)

Default constructor. Call init() that sets vpBiclops::DH1 Denavit-Hartenberg model.

computeMGD(*args, **kwargs)

Overloaded function.

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

Compute the direct geometric model of the camera: fMc

Warning

Provided for compatibility with previous versions. Use rather get_fMc(const vpColVector &, vpHomogeneousMatrix &).

Note

See get_fMc(const vpColVector &, vpHomogeneousMatrix &)

Parameters:
q

Joint 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.Biclops, q: visp._visp.core.ColVector) -> visp._visp.core.HomogeneousMatrix

Return the direct geometric model of the camera: fMc

Note

See get_fMc(const vpColVector &)

Parameters:
q

Joint 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.Biclops, q: visp._visp.core.ColVector, fPc: visp._visp.core.PoseVector) -> None

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

Warning

Provided for compatibility with previous versions. Use rather get_fMc(const vpColVector &, vpPoseVector &).

Note

See get_fMc(const vpColVector &, vpPoseVector &)

Parameters:
q

Joint position for pan and tilt axis.

fPc

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

getDenavitHartenbergModel(self) visp._visp.robot.Biclops.DenavitHartenbergModel

Return the Denavit-Hartenberg representation used to model the head.

Note

See vpBiclops::DenavitHartenbergModel

get_cMe(self) visp._visp.core.HomogeneousMatrix

Return the transformation \({^c}{\bf M}_e\) between the camera frame and the end effector frame.

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.

Parameters:
cVe: visp._visp.core.VelocityTwistMatrix

Twist transformation between camera and end effector frame to express a velocity skew from end effector frame in camera frame.

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

Joint 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

Joint 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).

get_fMc(*args, **kwargs)

Overloaded function.

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

Compute the direct geometric model of the camera: fMc

Parameters:
q

Joint 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. get_fMc(self: visp._visp.robot.Biclops, q: visp._visp.core.ColVector, fPc: visp._visp.core.PoseVector) -> None

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

Parameters:
q

Joint position for pan and tilt axis.

fPc

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

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

Return the direct geometric model of the camera: fMc

Parameters:
q

Joint 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.

get_fMe(self, q: visp._visp.core.ColVector) visp._visp.core.HomogeneousMatrix

Return the direct geometric model of the end effector: fMe

Parameters:
q: visp._visp.core.ColVector

Joint position for pan and tilt axis.

Returns:

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

init(self) None

Initialization.

  • By default vpBiclops::DH1 Denavit-Hartenberg model is selected.

  • Initialize also the default \({^c}{\bf M}_e\) transformation calling set_cMe() .

    \[\begin{split}{^c}{\bf M}_e = \left( \begin{matrix} 0 & 1 & 0 & 0 \\-1 & 0 & 0 & h \\0 & 0 & 1 & 0 \\0 & 0 & 0 & 1 \end{matrix} \right) \end{split}\]
setDenavitHartenbergModel(self, dh_model: visp._visp.robot.Biclops.DenavitHartenbergModel) None

Set the Denavit-Hartenberg representation used to model the head.

Note

See vpBiclops::DenavitHartenbergModel

Parameters:
dh_model: visp._visp.robot.Biclops.DenavitHartenbergModel

Denavit-Hartenberg model.

set_cMe(*args, **kwargs)

Overloaded function.

  1. set_cMe(self: visp._visp.robot.Biclops) -> None

Set the default 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.

\[\begin{split}{^c}{\bf M}_e = \left( \begin{matrix} 0 & 1 & 0 & 0 \\-1 & 0 & 0 & h \\0 & 0 & 1 & 0 \\0 & 0 & 0 & 1 \end{matrix} \right) \end{split}\]
  1. set_cMe(self: visp._visp.robot.Biclops, cMe: visp._visp.core.HomogeneousMatrix) -> None

Set the transformation between the camera frame and the end effector frame.