Visual Servoing Platform  version 3.5.0 under development (2022-02-15)

#include <visp3/robot/vpUnicycle.h>

+ Inheritance diagram for vpUnicycle:

Public Member Functions

 vpUnicycle ()
 
virtual ~vpUnicycle ()
 
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 Attributes

vpHomogeneousMatrix cMe_
 
vpMatrix eJe_
 

Detailed Description

Generic functions for unicycle mobile robots.

This class provides common features for unicycle mobile robots.

Examples:
mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, and mbot-apriltag-pbvs.cpp.

Definition at line 56 of file vpUnicycle.h.

Constructor & Destructor Documentation

◆ vpUnicycle()

vpUnicycle::vpUnicycle ( )
inline

Default constructor that does nothing.

Definition at line 62 of file vpUnicycle.h.

◆ ~vpUnicycle()

virtual vpUnicycle::~vpUnicycle ( )
inlinevirtual

Destructor that does nothing.

Definition at line 66 of file vpUnicycle.h.

Member Function Documentation

◆ get_cMe()

vpHomogeneousMatrix vpUnicycle::get_cMe ( ) const
inline

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
inline

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:
servoBiclopsPoint2DArtVelocity.cpp, 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
inline

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 get_cVe().

Referenced by get_cVe().

◆ get_eJe()

vpMatrix vpUnicycle::get_eJe ( ) const
inline

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()

void vpUnicycle::set_cMe ( const vpHomogeneousMatrix cMe)
inline

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::vpPioneerPan(), and vpPioneer::~vpPioneer().

◆ set_eJe()

void vpUnicycle::set_eJe ( const vpMatrix eJe)
inline

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::vpPioneerPan(), and vpPioneer::~vpPioneer().

Member Data Documentation

◆ cMe_

◆ eJe_

vpMatrix vpUnicycle::eJe_
protected

Definition at line 128 of file vpUnicycle.h.