Visual Servoing Platform  version 3.1.0

#include <visp3/robot/vpPioneerPan.h>

+ Inheritance diagram for vpPioneerPan:

Public Member Functions

 vpPioneerPan ()
 
virtual ~vpPioneerPan ()
 
Inherited functionalities from vpPioneerPan
void set_eJe (double q_pan)
 
Inherited functionalities from vpUnicycle
vpHomogeneousMatrix get_cMe () const
 
vpVelocityTwistMatrix get_cVe () const
 
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
vpMatrix get_eJe () const
 
void set_cMe (const vpHomogeneousMatrix &cMe)
 
void set_eJe (const vpMatrix &eJe)
 

Protected Member Functions

Protected Member Functions Inherited from vpPioneerPan
void set_cMe ()
 
void set_mMp ()
 
void set_pMe (const double q)
 

Protected Attributes

vpHomogeneousMatrix mMp_
 
vpHomogeneousMatrix pMe_
 
vpHomogeneousMatrix cMe_
 
vpMatrix eJe_
 

Detailed Description

Generic functions for Pioneer mobile robots equiped with a pan head.

This class provides common features for Pioneer mobile robots equiped with a pan head.

This robot has three control velocities $(v_x, w_z, \dot{q_1})$, the translational and rotational velocities of the mobile platform, the pan head velocity 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 pan axis.

pioneer-pan.png

Considering

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

with $(v_x, w_z)$ respectively the translational and rotational control velocities of the mobile platform, $\dot{q_1}$ the joint velocity of the pan head and $\bf v$ the six dimention velocity skew expressed at point E in frame E, the robot jacobian is given by:

\[ {^e}{\bf J}_e = \left(\begin{array}{ccc} c_1 & -c_1*p_y - s_1*p_x & 0 \\ 0 & 0 & 0 \\ s_1 & -s_1*p_y + c_1*p_x & 0 \\ 0 & 0 & 0 \\ 0 & -1 & 1 \\ 0 & 0 & 0 \\ \end{array} \right) \]

with $p_x, p_y$ the position of the head base frame in the mobile platform frame located at the middle point between the two weels.

Examples:
servoPioneerPanSegment3D.cpp.

Definition at line 97 of file vpPioneerPan.h.

Constructor & Destructor Documentation

◆ vpPioneerPan()

vpPioneerPan::vpPioneerPan ( )
inline

Create a pioneer mobile robot equiped with a pan head.

Definition at line 103 of file vpPioneerPan.h.

References vpUnicycle::set_cMe(), and vpUnicycle::set_eJe().

◆ ~vpPioneerPan()

virtual vpPioneerPan::~vpPioneerPan ( )
inlinevirtual

Destructor that does nothing.

Definition at line 115 of file vpPioneerPan.h.

Member Function Documentation

◆ get_cMe()

vpHomogeneousMatrix vpUnicycle::get_cMe ( ) const
inlineinherited

Return the tranformation ${^c}{\bf M}_e$ between the camera frame and the mobile robot end effector frame.

Definition at line 74 of file vpUnicycle.h.

◆ get_cVe() [1/2]

vpVelocityTwistMatrix vpUnicycle::get_cVe ( ) const
inlineinherited

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.

Examples:
servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 82 of file vpUnicycle.h.

References vpVelocityTwistMatrix::buildFrom().

◆ get_cVe() [2/2]

void vpUnicycle::get_cVe ( vpVelocityTwistMatrix cVe) const
inlineinherited

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.

See also
get_cVe()

Definition at line 97 of file vpUnicycle.h.

References vpUnicycle::get_cVe().

Referenced by vpUnicycle::get_cVe().

◆ get_eJe()

vpMatrix vpUnicycle::get_eJe ( ) const
inlineinherited

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 dimention velocity skew.
Examples:
servoPioneerPanSegment3D.cpp.

Definition at line 107 of file vpUnicycle.h.

Referenced by vpRobotPioneer::get_eJe(), vpSimulatorPioneer::get_eJe(), and vpSimulatorPioneerPan::get_eJe().

◆ set_cMe() [1/2]

void vpUnicycle::set_cMe ( const vpHomogeneousMatrix cMe)
inlineinherited

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

Definition at line 113 of file vpUnicycle.h.

Referenced by vpPioneer::vpPioneer(), vpPioneerPan(), and vpPioneer::~vpPioneer().

◆ set_cMe() [2/2]

void vpPioneerPan::set_cMe ( )
inlineprotected

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

Definition at line 175 of file vpPioneerPan.h.

References vpHomogeneousMatrix::buildFrom(), and vpHomogeneousMatrix::inverse().

◆ set_eJe() [1/2]

void vpUnicycle::set_eJe ( const vpMatrix eJe)
inlineinherited

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

Parameters
eJe: 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 dimention velocity skew.

Definition at line 123 of file vpUnicycle.h.

Referenced by vpPioneer::vpPioneer(), vpPioneerPan(), and vpPioneer::~vpPioneer().

◆ set_eJe() [2/2]

void vpPioneerPan::set_eJe ( double  q_pan)
inline

Set the robot jacobian expressed at point E the end effector frame located on the pan head.

Considering ${\bf v} = {^e}{\bf J}_e \; [v_x, w_z, \dot{q_1}]$ with $(v_x, w_z)$ respectively the translational and rotational control velocities of the mobile platform, $\dot{q_1}$ the joint velocity of the pan head and $\bf v$ the six dimention velocity skew expressed at point E in frame E, the robot jacobian is given by:

\[ {^e}{\bf J}_e = \left(\begin{array}{ccc} c_1 & -c_1*p_y - s_1*p_x & 0 \\ 0 & 0 & 0 \\ s_1 & -s_1*p_y + c_1*p_x & 0 \\ 0 & 0 & 0 \\ 0 & -1 & 1 \\ 0 & 0 & 0 \\ \end{array} \right) \]

with $p_x, p_y$ the position of the head base frame in the mobile platform frame located at the middle point between the two weels.

Examples:
servoPioneerPanSegment3D.cpp.

Definition at line 146 of file vpPioneerPan.h.

Referenced by vpSimulatorPioneerPan::setVelocity().

◆ set_mMp()

void vpPioneerPan::set_mMp ( )
inlineprotected

Set the transformation between the mobile platform frame located at the middle point between the two weels and the base frame of the pan head.

Definition at line 199 of file vpPioneerPan.h.

References vpTranslationVector::set().

◆ set_pMe()

void vpPioneerPan::set_pMe ( const double  q)
inlineprotected

Set the transformation between the pan head reference frame and the end-effector frame.

Parameters
q: Position in rad of the pan axis.

Definition at line 222 of file vpPioneerPan.h.

Referenced by vpSimulatorPioneerPan::setVelocity().

Member Data Documentation

◆ cMe_

◆ eJe_

vpMatrix vpUnicycle::eJe_
protectedinherited

Definition at line 128 of file vpUnicycle.h.

◆ mMp_

vpHomogeneousMatrix vpPioneerPan::mMp_
protected

◆ pMe_

vpHomogeneousMatrix vpPioneerPan::pMe_
protected