Pioneer

class Pioneer(self)

Bases: Unicycle

Generic functions for Pioneer mobile robots.

This class provides common features for Pioneer mobile robots. This robot has two control velocities \((v_x, w_z)\) , the translational and rotational velocities of the mobile platform respectively.

The figure below shows the position of the frames that are used to model the robot. The end effector frame is here located at the middle point between the two wheels.

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

The robot jacobian at the end effector frame, the point located at the middle between the two wheels is given by:

\[\begin{split}{^e}{\bf J}_e = \left(\begin{array}{cc} 1 & 0 \\0 & 0 \\0 & 0 \\0 & 0 \\0 & 0 \\0 & 1 \\\end{array} \right) \end{split}\]

Considering \((v_x, w_z)\) , it is possible to compute \(\bf v\) the six dimension velocity skew expressed at the end effector frame by:

\[\begin{split}{\bf v} = {^e}{\bf J}_e \; \left(\begin{array}{c} v_x \\w_z \\\end{array} \right) \end{split}\]

.

Create a default Pioneer robot.

Methods

__init__

Create a default Pioneer robot.

Inherited Methods

set_eJe

Set the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.

get_cMe

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

get_cVe

Overloaded function.

set_cMe

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

get_eJe

Return the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.

Operators

__doc__

__init__

Create a default Pioneer robot.

__module__

Attributes

__annotations__

__init__(self)

Create a default Pioneer robot.

get_cMe(self) visp._visp.core.HomogeneousMatrix

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

get_cVe(*args, **kwargs)

Overloaded function.

  1. get_cVe(self: visp._visp.robot.Unicycle) -> visp._visp.core.VelocityTwistMatrix

Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.

  1. get_cVe(self: visp._visp.robot.Unicycle, cVe: visp._visp.core.VelocityTwistMatrix) -> None

Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.

Note

See get_cVe()

get_eJe(self) visp._visp.core.Matrix

Return the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.

Returns:

The robot jacobian such as \({\bf v} = {^e}{\bf J}_e \; \dot{\bf q}\) with \(\dot{\bf q} = (v_x, w_z)\) the robot control velocities and \(\bf v\) the six dimension velocity skew.

set_cMe(self, cMe: visp._visp.core.HomogeneousMatrix) None

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

set_eJe(self, eJe: visp._visp.core.Matrix) None

Set the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.

Parameters:
eJe: visp._visp.core.Matrix

The robot jacobian to set such as \({\bf v} = {^e}{\bf J}_e \; \dot{\bf q}\) with \(\dot{\bf q} = (v_x, w_z)\) the robot control velocities and \(\bf v\) the six dimension velocity skew.