Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpRobotPtu46 Class Reference

#include <visp3/robot/vpRobotPtu46.h>

+ Inheritance diagram for vpRobotPtu46:

Public Types

enum  vpRobotStateType {
  STATE_STOP, STATE_VELOCITY_CONTROL, STATE_POSITION_CONTROL, STATE_ACCELERATION_CONTROL,
  STATE_FORCE_TORQUE_CONTROL
}
 
enum  vpControlFrameType {
  REFERENCE_FRAME, ARTICULAR_FRAME, JOINT_STATE = ARTICULAR_FRAME, END_EFFECTOR_FRAME,
  CAMERA_FRAME, TOOL_FRAME = CAMERA_FRAME, MIXT_FRAME
}
 

Public Member Functions

 vpRobotPtu46 (const char *device="/dev/ttyS0")
 
 vpRobotPtu46 (vpRobotPtu46 *pub)
 
virtual ~vpRobotPtu46 (void)
 
void get_cMe (vpHomogeneousMatrix &_cMe) const
 
void get_cVe (vpVelocityTwistMatrix &_cVe) const
 
void get_eJe (vpMatrix &_eJe)
 
void get_fJe (vpMatrix &_fJe)
 
void getDisplacement (vpRobot::vpControlFrameType frame, vpColVector &q)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
double getPositioningVelocity (void)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &q_dot)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
void init (void)
 
bool readPositionFile (const std::string &filename, vpColVector &q)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q)
 
void setPosition (const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
 
void setPosition (const char *filename)
 
void setPositioningVelocity (double velocity)
 
vpRobot::vpRobotStateType setRobotState (vpRobot::vpRobotStateType newState)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &q_dot)
 
void stopMotion ()
 
Inherited functionalities from vpPtu46
void computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
vpHomogeneousMatrix computeMGD (const vpColVector &q) const
 
void computeMGD (const vpColVector &q, vpPoseVector &r) const
 
void get_eJe (const vpColVector &q, vpMatrix &eJe) const
 
void get_fJe (const vpColVector &q, vpMatrix &fJe) const
 
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxRotationVelocity (double maxVr)
 
void setMaxTranslationVelocity (double maxVt)
 
void setVerbose (bool verbose)
 

Static Public Member Functions

Static Public Member Functions inherited from vpRobot
static vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
 

Static Public Attributes

static const double defaultPositioningVelocity = 10.0
 
static const unsigned int ndof = 2
 
static const float L = 0.0765f
 
static const float h = 0.068f
 

Protected Member Functions

Protected Member Functions Inherited from vpRobot
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void) const
 

Protected Attributes

double maxTranslationVelocity
 
double maxRotationVelocity
 
int nDof
 
vpMatrix eJe
 
int eJeAvailable
 
vpMatrix fJe
 
int fJeAvailable
 
int areJointLimitsAvailable
 
double * qmin
 
double * qmax
 
bool verbose_
 

Static Protected Attributes

static const double maxTranslationVelocityDefault = 0.2
 
static const double maxRotationVelocityDefault = 0.7
 

Detailed Description

Interface for the Directed Perception ptu-46 pan, tilt head .

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

This class provide a position and a speed control interface for the ptu-46 head.

Examples:
movePtu46.cpp, and servoPtu46Point2DArtVelocity.cpp.

Definition at line 80 of file vpRobotPtu46.h.

Member Enumeration Documentation

◆ vpControlFrameType

Robot control frames.

Enumerator
REFERENCE_FRAME 

Corresponds to a fixed reference frame attached to the robot structure.

ARTICULAR_FRAME 

Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE.

JOINT_STATE 

Corresponds to the joint state.

END_EFFECTOR_FRAME 

Corresponds to robot end-effector frame.

CAMERA_FRAME 

Corresponds to a frame attached to the camera mounted on the robot end-effector.

TOOL_FRAME 

Corresponds to a frame attached to the tool (camera, gripper...) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME.

MIXT_FRAME 

Corresponds to a "virtual" frame where translations are expressed in the reference frame, and rotations in the camera frame.

Definition at line 75 of file vpRobot.h.

◆ vpRobotStateType

enum vpRobot::vpRobotStateType
inherited

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

◆ vpRobotPtu46() [1/2]

vpRobotPtu46::vpRobotPtu46 ( const char *  device = "/dev/ttyS0")
explicit

Default constructor.

Initialize the ptu-46 pan, tilt head by opening the serial port.

See also
init()

Definition at line 72 of file vpRobotPtu46.cpp.

References defaultPositioningVelocity, init(), setRobotState(), vpRobot::STATE_STOP, vpDEBUG_TRACE, and vpERROR_TRACE.

◆ vpRobotPtu46() [2/2]

vpRobotPtu46::vpRobotPtu46 ( vpRobotPtu46 pub)
explicit

◆ ~vpRobotPtu46()

vpRobotPtu46::~vpRobotPtu46 ( void  )
virtual

Destructor. Close the serial connection with the head.

Definition at line 108 of file vpRobotPtu46.cpp.

References setRobotState(), vpRobot::STATE_STOP, and vpERROR_TRACE.

Member Function Documentation

◆ computeMGD() [1/3]

void vpPtu46::computeMGD ( const vpColVector q,
vpHomogeneousMatrix fMc 
) const
inherited

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.

Definition at line 70 of file vpPtu46.cpp.

References vpException::dimensionError, vpArray2D< Type >::getRows(), vpPtu46::h, vpPtu46::L, vpCDEBUG, and vpERROR_TRACE.

Referenced by vpPtu46::computeMGD().

◆ computeMGD() [2/3]

vpHomogeneousMatrix vpPtu46::computeMGD ( const vpColVector q) const
inherited

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.

Definition at line 120 of file vpPtu46.cpp.

References vpPtu46::computeMGD().

◆ computeMGD() [3/3]

void vpPtu46::computeMGD ( const vpColVector q,
vpPoseVector r 
) const
inherited

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.

Definition at line 138 of file vpPtu46.cpp.

References vpPoseVector::buildFrom(), vpPtu46::computeMGD(), and vpHomogeneousMatrix::inverse().

◆ get_cMe()

void vpRobotPtu46::get_cMe ( vpHomogeneousMatrix cMe) const

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.

Parameters
cMe: Homogeneous matrix between camera and end effector frame.

Definition at line 228 of file vpRobotPtu46.cpp.

References vpPtu46::get_cMe().

◆ get_cVe()

void vpRobotPtu46::get_cVe ( vpVelocityTwistMatrix cVe) const

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: Twist transformation between camera and end effector frame to expess a velocity skew from end effector frame in camera frame.
Examples:
servoPtu46Point2DArtVelocity.cpp.

Definition at line 211 of file vpRobotPtu46.cpp.

References vpVelocityTwistMatrix::buildFrom(), and vpPtu46::get_cMe().

◆ get_eJe() [1/2]

void vpPtu46::get_eJe ( const vpColVector q,
vpMatrix eJe 
) const
inherited

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: Articular position for pan and tilt axis.
eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Definition at line 249 of file vpPtu46.cpp.

References vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.

Referenced by get_eJe().

◆ get_eJe() [2/2]

void vpRobotPtu46::get_eJe ( vpMatrix eJe)
virtual

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
eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Implements vpRobot.

Examples:
servoPtu46Point2DArtVelocity.cpp.

Definition at line 240 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpPtu46::get_eJe(), getPosition(), and vpERROR_TRACE.

◆ get_fJe() [1/2]

void vpPtu46::get_fJe ( const vpColVector q,
vpMatrix fJe 
) const
inherited

Get the robot jacobian expressed in the robot reference frame

Parameters
q: Articular position for pan and tilt axis.
fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Definition at line 278 of file vpPtu46.cpp.

References vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.

Referenced by get_fJe().

◆ get_fJe() [2/2]

void vpRobotPtu46::get_fJe ( vpMatrix fJe)
virtual

Get the robot jacobian expressed in the robot reference frame

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

Implements vpRobot.

Definition at line 260 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpPtu46::get_fJe(), getPosition(), and vpERROR_TRACE.

◆ getDisplacement()

void vpRobotPtu46::getDisplacement ( vpRobot::vpControlFrameType  frame,
vpColVector d 
)
virtual

Get the robot displacement since the last call of this method.

Warning
The first call of this method gives not a good value for the displacement.
Parameters
frameThe frame in which the measured displacement is expressed.
dThe displacement:
  • In articular, the dimension of q is 2 (the number of axis of the robot) with respectively d[0] (pan displacement), d[1] (tilt displacement).
  • In camera frame, the dimension of d is 6 (tx, ty, ty, rx, ry, rz). Translations are expressed in meters, rotations in radians.
Exceptions
vpRobotException::wrongStateErrorIf a not supported frame type is given.

Implements vpRobot.

Definition at line 738 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpRobotException::wrongStateError.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

◆ getPosition() [1/2]

void vpRobotPtu46::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
virtual

Return the position of each axis.

Parameters
frame: Control frame. This head can only be controlled in articular.
q: The position of the axis.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Examples:
movePtu46.cpp.

Definition at line 414 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpDEBUG_TRACE, vpERROR_TRACE, and vpRobotException::wrongStateError.

Referenced by get_eJe(), and get_fJe().

◆ getPosition() [2/2]

vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)
inherited

Return the current robot position in the specified frame.

Definition at line 216 of file vpRobot.cpp.

References vpRobot::getPosition().

◆ getPositioningVelocity()

double vpRobotPtu46::getPositioningVelocity ( void  )

Get the velocity in % used for a position control.

Returns
Positionning velocity in [0, 100]

Definition at line 286 of file vpRobotPtu46.cpp.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

◆ getRobotState()

virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtualinherited

◆ getVelocity() [1/2]

void vpRobotPtu46::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector q_dot 
)

Get the articular velocity.

Parameters
frame: Control frame. This head can only be controlled in articular.
q_dot: The measured articular velocity in rad/s.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Definition at line 586 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpRobotException::wrongStateError.

Referenced by getVelocity().

◆ getVelocity() [2/2]

vpColVector vpRobotPtu46::getVelocity ( const vpRobot::vpControlFrameType  frame)

Return the articular velocity.

Parameters
frame: Control frame. This head can only be controlled in articular.
Returns
The measured articular velocity in rad/s.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Definition at line 634 of file vpRobotPtu46.cpp.

References getVelocity().

◆ init()

void vpRobotPtu46::init ( void  )
virtual

Open the serial port.

Exceptions
vpRobotException::constructionError: If the device cannot be oppened.

Implements vpRobot.

Definition at line 140 of file vpRobotPtu46.cpp.

References vpRobotException::constructionError, vpDEBUG_TRACE, and vpERROR_TRACE.

Referenced by vpRobotPtu46().

◆ readPositionFile()

bool vpRobotPtu46::readPositionFile ( const std::string &  filename,
vpColVector q 
)

Get an articular position from the position file.

Parameters
filename: Position file.
q: The articular position read in the file.
# Example of ptu-46 position file
# The axis positions must be preceed by R:
# First value : pan articular position in degrees
# Second value: tilt articular position in degrees
R: 15.0 5.0
Returns
true if a position was found, false otherwise.

Definition at line 661 of file vpRobotPtu46.cpp.

References vpColVector::deg2rad(), vpPtu46::ndof, vpColVector::resize(), and vpIoTools::splitChain().

Referenced by setPosition().

◆ saturateVelocities()

vpColVector vpRobot::saturateVelocities ( const vpColVector v_in,
const vpColVector v_max,
bool  verbose = false 
)
staticinherited

Saturate velocities.

Parameters
v_in: Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
v_max: Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
verbose: Print a message indicating which axis causes the saturation.
Returns
Saturated velocities.
Exceptions
vpRobotException::dimensionError: If the input vectors have different dimensions.

The code below shows how to use this static method in order to saturate a velocity skew vector.

#include <iostream>
#include <visp3/robot/vpRobot.h>
int main()
{
// Set a velocity skew vector
v[0] = 0.1; // vx in m/s
v[1] = 0.2; // vy
v[2] = 0.3; // vz
v[3] = vpMath::rad(10); // wx in rad/s
v[4] = vpMath::rad(-10); // wy
v[5] = vpMath::rad(20); // wz
// Set the maximal allowed velocities
vpColVector v_max(6);
for (int i=0; i<3; i++)
v_max[i] = 0.3; // in translation (m/s)
for (int i=3; i<6; i++)
v_max[i] = vpMath::rad(10); // in rotation (rad/s)
// Compute the saturated velocity skew vector
vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
std::cout << "v : " << v.t() << std::endl;
std::cout << "v max: " << v_max.t() << std::endl;
std::cout << "v sat: " << v_sat.t() << std::endl;
return 0;
}

Definition at line 163 of file vpRobot.cpp.

References vpException::dimensionError, and vpArray2D< Type >::size().

Referenced by vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)
inherited

◆ setMaxTranslationVelocity()

void vpRobot::setMaxTranslationVelocity ( double  v_max)
inherited

Set the maximal translation velocity that can be sent to the robot during a velocity control.

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples:
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, and testFeatureSegment.cpp.

Definition at line 239 of file vpRobot.cpp.

References vpRobot::maxTranslationVelocity.

Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().

◆ setPosition() [1/3]

void vpRobotPtu46::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector q 
)
virtual

Move the robot in position control.

Warning
This method is blocking. That mean that it waits the end of the positionning.
Parameters
frame: Control frame. This head can only be controlled in articular.
q: The position to set for each axis.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Examples:
movePtu46.cpp, and servoPtu46Point2DArtVelocity.cpp.

Definition at line 304 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpERROR_TRACE, and vpRobotException::wrongStateError.

Referenced by setPosition().

◆ setPosition() [2/3]

void vpRobotPtu46::setPosition ( const vpRobot::vpControlFrameType  frame,
const double &  q1,
const double &  q2 
)

Move the robot in position control.

Warning
This method is blocking. That mean that it wait the end of the positionning.
Parameters
frame: Control frame. This head can only be controlled in articular.
q1: The pan position to set.
q2: The tilt position to set.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Definition at line 364 of file vpRobotPtu46.cpp.

References setPosition(), and vpERROR_TRACE.

◆ setPosition() [3/3]

void vpRobotPtu46::setPosition ( const char *  filename)

Read the content of the position file and moves to head to articular position.

Parameters
filename: Position filename
Exceptions
vpRobotException::readingParametersError: If the articular position cannot be read from file.
See also
readPositionFile()

Definition at line 391 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobotException::readingParametersError, readPositionFile(), setPosition(), and vpERROR_TRACE.

◆ setPositioningVelocity()

void vpRobotPtu46::setPositioningVelocity ( double  velocity)

Set the velocity used for a position control.

Parameters
velocity: Velocity in % of the maximum velocity between [0,100].

Definition at line 279 of file vpRobotPtu46.cpp.

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotPtu46::setRobotState ( vpRobot::vpRobotStateType  newState)
virtual

Change the state of the robot either to stop them, or to set position or speed control.

Reimplemented from vpRobot.

Examples:
movePtu46.cpp, and servoPtu46Point2DArtVelocity.cpp.

Definition at line 158 of file vpRobotPtu46.cpp.

References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and vpDEBUG_TRACE.

Referenced by setPosition(), stopMotion(), vpRobotPtu46(), and ~vpRobotPtu46().

◆ setVelocity()

void vpRobotPtu46::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector v 
)
virtual

Send a velocity on each axis.

Parameters
frame: Control frame. This head can only be controlled in articular and camera frame. Be aware, the reference frame (vpRobot::REFERENCE_FRAME) end-effector frame (vpRobot::END_EFFECTOR_FRAME) and the mixt frame (vpRobot::MIXT_FRAME) are not implemented.
v: The desired velocity of the axis. The size of this vector is always 2. Velocities are expressed in rad/s.
  • In camera frame, $ v = [\omega_x, \omega_y]^t $ expressed in rad/s.
  • In articular, we control the 2 dof, $ v = [\dot{q}_1, \dot{q}_2]^t $ with $ \dot{q}_1 $ the pan of the camera and $ \dot{q}_2$ the tilt of the camera in rad/s.
Exceptions
vpRobotException::wrongStateError: If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity().
vpRobotException::wrongStateError: If a non supported frame type (vpRobot::REFERENCE_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::MIXT_FRAME) is given.
Warning
Velocities could be saturated if one of them exceed the maximal autorized speed (see vpRobot::maxRotationVelocity).

Implements vpRobot.

Examples:
movePtu46.cpp, and servoPtu46Point2DArtVelocity.cpp.

Definition at line 482 of file vpRobotPtu46.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobot::maxRotationVelocity, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::STATE_VELOCITY_CONTROL, vpCDEBUG, vpDEBUG_TRACE, vpERROR_TRACE, and vpRobotException::wrongStateError.

◆ setVerbose()

◆ stopMotion()

void vpRobotPtu46::stopMotion ( void  )

Halt all the axis.

Definition at line 195 of file vpRobotPtu46.cpp.

References setRobotState(), and vpRobot::STATE_STOP.

Member Data Documentation

◆ areJointLimitsAvailable

◆ defaultPositioningVelocity

const double vpRobotPtu46::defaultPositioningVelocity = 10.0
static

Definition at line 97 of file vpRobotPtu46.h.

Referenced by vpRobotPtu46().

◆ eJe

vpMatrix vpRobot::eJe
protectedinherited

◆ eJeAvailable

int vpRobot::eJeAvailable
protectedinherited

is the robot Jacobian expressed in the end-effector frame available

Definition at line 106 of file vpRobot.h.

Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().

◆ fJe

vpMatrix vpRobot::fJe
protectedinherited

robot Jacobian expressed in the robot reference frame available

Definition at line 108 of file vpRobot.h.

Referenced by vpRobotFlirPtu::get_fJe(), and vpRobot::operator=().

◆ fJeAvailable

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 110 of file vpRobot.h.

Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().

◆ h

const float vpPtu46::h = 0.068f
staticinherited

Horizontal offset along the last joint, from last joint to camera frame.

Definition at line 82 of file vpPtu46.h.

Referenced by vpPtu46::computeMGD(), and vpPtu46::get_cMe().

◆ L

const float vpPtu46::L = 0.0765f
staticinherited

Geometric model

Definition at line 81 of file vpPtu46.h.

Referenced by vpPtu46::computeMGD(), and vpPtu46::get_cMe().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

Referenced by vpRobotTemplate::init(), and vpRobotFlirPtu::init().

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 97 of file vpRobot.h.

Referenced by vpRobotTemplate::init(), and vpRobotFlirPtu::init().

◆ ndof

const unsigned int vpPtu46::ndof = 2
staticinherited

Nombre d'articulations du robot. Number of dof

Definition at line 78 of file vpPtu46.h.

Referenced by getDisplacement(), getPosition(), getVelocity(), and readPositionFile().

◆ nDof

◆ qmax

◆ qmin

◆ verbose_