Visual Servoing Platform  version 3.6.1 under development (2024-11-21)
vpRobotBiclops Class Reference

#include <visp3/robot/vpRobotBiclops.h>

+ Inheritance diagram for vpRobotBiclops:

Public Types

enum  DenavitHartenbergModel { DH1 , DH2 }
 
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

 vpRobotBiclops ()
 
VP_EXPLICIT vpRobotBiclops (const std::string &filename)
 
virtual ~vpRobotBiclops ()
 
void init () VP_OVERRIDE
 
void get_cMe (vpHomogeneousMatrix &cMe) const
 
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
void get_eJe (vpMatrix &eJe) VP_OVERRIDE
 
void get_fJe (vpMatrix &fJe) VP_OVERRIDE
 
void getDisplacement (const vpRobot::vpControlFrameType frame, vpColVector &d) VP_OVERRIDE
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
 
double getPositioningVelocity (void)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &q_dot)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
bool readPositionFile (const std::string &filename, vpColVector &q)
 
void setConfigFile (const std::string &filename="/usr/share/BiclopsDefault.cfg")
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
 
void setPosition (const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
 
void setPosition (const std::string &filename)
 
void setPositioningVelocity (double velocity)
 
vpRobot::vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState) VP_OVERRIDE
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &q_dot) VP_OVERRIDE
 
void stopMotion ()
 
Inherited functionalities from vpBiclops
void computeMGD (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
vpHomogeneousMatrix computeMGD (const vpColVector &q) const
 
void computeMGD (const vpColVector &q, vpPoseVector &fPc) const
 
vpHomogeneousMatrix get_cMe () const
 
void get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const
 
void get_fMc (const vpColVector &q, vpPoseVector &fPc) const
 
vpHomogeneousMatrix get_fMc (const vpColVector &q) const
 
vpHomogeneousMatrix get_fMe (const vpColVector &q) const
 
void get_eJe (const vpColVector &q, vpMatrix &eJe) const
 
void get_fJe (const vpColVector &q, vpMatrix &fJe) const
 
vpBiclops::DenavitHartenbergModel getDenavitHartenbergModel () const
 
void set_cMe ()
 
void set_cMe (const vpHomogeneousMatrix &cMe)
 
void setDenavitHartenbergModel (vpBiclops::DenavitHartenbergModel dh_model=vpBiclops::DH1)
 
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
int getNDof () 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 void vpRobotBiclopsSpeedControlLoop (void *arg)
 
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 h = 0.048f
 
static const float panJointLimit = (float)(M_PI)
 
static const float tiltJointLimit = (float)(M_PI / 4.5)
 
static const float speedLimit = (float)(M_PI / 3.0)
 

Protected Member Functions

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

Protected Attributes

DenavitHartenbergModel m_dh_model
 
vpHomogeneousMatrix m_cMe
 
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 Biclops, pan, tilt head control.

Two different models are proposed and can be set using vpBiclops::DenavitHartenbergModel. The vpBiclops::DH1 and vpBiclops::DH2 model differ in the orientation of the tilt axis. The following image gives the location of the end-effector frame and a potential camera frame.

Biclops PT models

See http://www.traclabs.com/biclopspt.html for more details.

This class provide a position and a speed control interface for the Biclops head. To manage the Biclops joint limits in speed control, a control loop is running in a separate thread implemented in vpRobotBiclopsSpeedControlLoop().

Warning
Velocity control mode is not exported from the top-level Biclops API class provided by Traclabs. That means that there is no protection in this mode to prevent an axis from striking its hard limit. In position mode, Traclabs put soft limits in that keep any command from driving to a position too close to the hard limits. In velocity mode this protection does not exist in the current API.
With the understanding that hitting the hard limits at full speed/power can damage the unit, damage due to velocity mode commanding is under user responsibility.
Examples
moveBiclops.cpp, servoBiclopsPoint2DArtVelocity.cpp, and servoPioneerPanSegment3D.cpp.

Definition at line 91 of file vpRobotBiclops.h.

Member Enumeration Documentation

◆ DenavitHartenbergModel

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.

Biclops PT models

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

Joint $a_i$ $d_i$ $\alpha_i$ $\theta_i$
1 0 0 $-\pi/2$ $q_1$
2 0 0 $ \pi/2$ $q_2 + \pi/2$

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

Joint $a_i$ $d_i$ $\alpha_i$ $\theta_i$
1 0 0 $ \pi/2$ $q_1$
2 0 0 $-\pi/2$ $q_2 - \pi/2$

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

Enumerator
DH1 

First Denavit-Hartenberg representation.

DH2 

Second Denavit-Hartenberg representation.

Definition at line 94 of file vpBiclops.h.

◆ 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 76 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

◆ vpRobotBiclops() [1/2]

vpRobotBiclops::vpRobotBiclops ( )

Default constructor.

Does nothing more than setting the default configuration file to /usr/share/BiclopsDefault.cfg.

As shown in the following example, the turret need to be initialized using init() function.

#include <visp3/robot/vpRobotBiclops.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#ifdef VISP_HAVE_BICLOPS
vpRobotBiclops robot; // Use the default config file in /usr/share/BiclopsDefault.cfg
// Initialize the head
robot.init();
// Move the robot to a specified pan and tilt
q[0] = vpMath::rad(20); // pan
q[1] = vpMath::rad(40); // tilt
robot.setPosition(vpRobot::JOINT_STATE, q);
#endif
return 0;
}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
static double rad(double deg)
Definition: vpMath.h:129
Interface for the Biclops, pan, tilt head control.
@ JOINT_STATE
Definition: vpRobot.h:82
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202

Definition at line 73 of file vpRobotBiclops.cpp.

References setConfigFile().

◆ vpRobotBiclops() [2/2]

vpRobotBiclops::vpRobotBiclops ( const std::string &  filename)

Constructor that initialize the Biclops pan, tilt head by reading the configuration file provided by Traclabs and do the homing sequence.

The following example shows how to use the constructor.

#include <visp3/robot/vpRobotBiclops.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#ifdef VISP_HAVE_BICLOPS
// Specify the config file location and initialize the turret
vpRobotBiclops robot("/usr/share/BiclopsDefault.cfg");
// Move the robot to a specified pan and tilt
q[0] = vpMath::rad(-20); // pan
q[1] = vpMath::rad(10); // tilt
robot.setPosition(vpRobot::JOINT_STATE, q);
#endif
return 0;
}

Definition at line 83 of file vpRobotBiclops.cpp.

References init(), and setConfigFile().

◆ ~vpRobotBiclops()

vpRobotBiclops::~vpRobotBiclops ( )
virtual

Destructor. Wait the end of the control thread.

Definition at line 95 of file vpRobotBiclops.cpp.

References setRobotState(), and vpRobot::STATE_STOP.

Member Function Documentation

◆ computeMGD() [1/3]

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

Return the direct geometric model of the camera: fMc

Warning
Provided for compatibility with previous versions. Use rather 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.
See also
get_fMc(const vpColVector &)

Definition at line 67 of file vpBiclops.cpp.

References vpBiclops::computeMGD().

◆ computeMGD() [2/3]

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

Compute the direct geometric model of the camera: fMc

Warning
Provided for compatibility with previous versions. Use rather 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.
See also
get_fMc(const vpColVector &, vpHomogeneousMatrix &)

Definition at line 47 of file vpBiclops.cpp.

References vpBiclops::get_fMe(), vpHomogeneousMatrix::inverse(), and vpBiclops::m_cMe.

Referenced by vpBiclops::computeMGD().

◆ computeMGD() [3/3]

void vpBiclops::computeMGD ( const vpColVector q,
vpPoseVector fPc 
) const
inherited

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 &).
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.
See also
get_fMc(const vpColVector &, vpPoseVector &)

Definition at line 147 of file vpBiclops.cpp.

References vpPoseVector::buildFrom(), vpBiclops::get_fMc(), and vpHomogeneousMatrix::inverse().

◆ get_cMe() [1/2]

vpHomogeneousMatrix vpBiclops::get_cMe ( ) const
inlineinherited

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

Definition at line 195 of file vpBiclops.h.

Referenced by get_cMe(), and get_cVe().

◆ get_cMe() [2/2]

void vpRobotBiclops::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 438 of file vpRobotBiclops.cpp.

References vpBiclops::get_cMe().

◆ get_cVe()

void vpRobotBiclops::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 express a velocity skew from end effector frame in camera frame.

Definition at line 430 of file vpRobotBiclops.cpp.

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

◆ get_eJe() [1/2]

void vpBiclops::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
[in]q: Joint position for pan and tilt axis.
[out]eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Definition at line 212 of file vpBiclops.cpp.

References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), vpBiclops::m_dh_model, and vpArray2D< Type >::resize().

Referenced by get_eJe().

◆ get_eJe() [2/2]

void vpRobotBiclops::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.

Definition at line 440 of file vpRobotBiclops.cpp.

References vpRobot::eJe, vpBiclops::get_eJe(), getPosition(), and vpRobot::JOINT_STATE.

◆ get_fJe() [1/2]

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

Get the robot jacobian expressed in the robot reference frame

Parameters
[in]q: Joint position for pan and tilt axis.
[out]fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Definition at line 237 of file vpBiclops.cpp.

References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), vpBiclops::m_dh_model, and vpArray2D< Type >::resize().

Referenced by get_fJe().

◆ get_fJe() [2/2]

void vpRobotBiclops::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 448 of file vpRobotBiclops.cpp.

References vpRobot::fJe, vpBiclops::get_fJe(), getPosition(), and vpRobot::JOINT_STATE.

◆ get_fMc() [1/3]

vpHomogeneousMatrix vpBiclops::get_fMc ( const vpColVector q) const
inherited

Return the direct geometric model of the camera: fMc

Parameters
[in]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.

Definition at line 76 of file vpBiclops.cpp.

References vpBiclops::get_fMc().

◆ get_fMc() [2/3]

void vpBiclops::get_fMc ( const vpColVector q,
vpHomogeneousMatrix fMc 
) const
inherited

Compute the direct geometric model of the camera: fMc

Parameters
[in]q: Joint position for pan and tilt axis.
[out]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 57 of file vpBiclops.cpp.

References vpBiclops::get_fMe(), vpHomogeneousMatrix::inverse(), and vpBiclops::m_cMe.

Referenced by vpBiclops::computeMGD(), vpBiclops::get_fMc(), and getDisplacement().

◆ get_fMc() [3/3]

void vpBiclops::get_fMc ( const vpColVector q,
vpPoseVector fPc 
) const
inherited

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

Parameters
[in]q: Joint position for pan and tilt axis.
[out]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.

Definition at line 157 of file vpBiclops.cpp.

References vpPoseVector::buildFrom(), vpBiclops::get_fMc(), and vpHomogeneousMatrix::inverse().

◆ get_fMe()

vpHomogeneousMatrix vpBiclops::get_fMe ( const vpColVector q) const
inherited

Return the direct geometric model of the end effector: fMe

Parameters
[in]q: 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.

Definition at line 85 of file vpBiclops.cpp.

References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), and vpBiclops::m_dh_model.

Referenced by vpBiclops::computeMGD(), and vpBiclops::get_fMc().

◆ getDenavitHartenbergModel()

vpBiclops::DenavitHartenbergModel vpBiclops::getDenavitHartenbergModel ( ) const
inlineinherited

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

See also
vpBiclops::DenavitHartenbergModel

Definition at line 278 of file vpBiclops.h.

◆ getDisplacement()

void vpRobotBiclops::getDisplacement ( const 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 joint state, 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, tux, tuy, tuz). Translations are expressed in meters, rotations in radians with the theta U representation.
Exceptions
vpRobotException::wrongStateErrorIf a not supported frame type is given.

Implements vpRobot.

Definition at line 812 of file vpRobotBiclops.cpp.

References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpBiclops::get_fMc(), getPosition(), vpHomogeneousMatrix::inverse(), vpExponentialMap::inverse(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, and vpRobotException::wrongStateError.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited

◆ getNDof()

int vpRobot::getNDof ( ) const
inlineinherited

Return robot degrees of freedom number.

Examples
servoPololuPtuPoint2DJointVelocity.cpp.

Definition at line 145 of file vpRobot.h.

◆ getPosition() [1/2]

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

Return the current robot position in the specified frame.

Definition at line 217 of file vpRobot.cpp.

References vpRobot::getPosition().

◆ getPosition() [2/2]

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

Return the position of each axis.

  • In positioning control mode, call vpRobotBiclopsController::getPosition()
  • In speed control mode, call vpRobotBiclopsController::getActualPosition()
Parameters
frame: Control frame. This Biclops head can only be controlled in joint state.
q: The position of the axis in radians.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Examples
servoPioneerPanSegment3D.cpp.

Definition at line 531 of file vpRobotBiclops.cpp.

References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.

Referenced by get_eJe(), get_fJe(), and getDisplacement().

◆ getPositioningVelocity()

double vpRobotBiclops::getPositioningVelocity ( void  )

Get the velocity in % used for a position control.

Returns
Positioning velocity in [0, 100.0]. The maximum positioning velocity is given vpBiclops::speedLimit.

Definition at line 466 of file vpRobotBiclops.cpp.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

Definition at line 183 of file vpRobot.h.

◆ getRobotState()

◆ getVelocity() [1/2]

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

Return the joint velocity.

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

Definition at line 746 of file vpRobotBiclops.cpp.

References getVelocity().

◆ getVelocity() [2/2]

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

Get the joint velocity.

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

Definition at line 683 of file vpRobotBiclops.cpp.

References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.

Referenced by getVelocity().

◆ init()

void vpRobotBiclops::init ( void  )
virtual

Set the Biclops config filename. Check if the config file exists and initialize the head.

Exceptions
vpRobotException::constructionErrorIf the config file cannot be opened.

Implements vpRobot.

Definition at line 116 of file vpRobotBiclops.cpp.

References vpRobotException::constructionError, vpBiclops::ndof, vpColVector::resize(), setRobotState(), and vpRobot::STATE_STOP.

Referenced by vpRobotBiclops().

◆ readPositionFile()

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

Get joint positions from the position file.

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

Definition at line 754 of file vpRobotBiclops.cpp.

References vpColVector::deg2rad(), vpBiclops::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>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
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;
}
vpRowVector t() const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164

Definition at line 164 of file vpRobot.cpp.

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

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

◆ set_cMe() [1/2]

void vpBiclops::set_cMe ( )
inherited

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.

\[ {^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) \]

Definition at line 187 of file vpBiclops.cpp.

References vpBiclops::h, and vpBiclops::m_cMe.

Referenced by vpBiclops::init().

◆ set_cMe() [2/2]

void vpBiclops::set_cMe ( const vpHomogeneousMatrix cMe)
inlineinherited

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

Definition at line 302 of file vpBiclops.h.

◆ setConfigFile()

void vpRobotBiclops::setConfigFile ( const std::string &  filename = "/usr/share/BiclopsDefault.cfg")

Set the Biclops config filename.

Definition at line 114 of file vpRobotBiclops.cpp.

Referenced by vpRobotBiclops().

◆ setDenavitHartenbergModel()

void vpBiclops::setDenavitHartenbergModel ( vpBiclops::DenavitHartenbergModel  dh_model = vpBiclops::DH1)
inlineinherited

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

Parameters
[in]dh_model: Denavit-Hartenberg model.
See also
vpBiclops::DenavitHartenbergModel
Examples
servoPioneerPanSegment3D.cpp.

Definition at line 309 of file vpBiclops.h.

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)
inherited

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

Parameters
w_max: Maximum rotational velocity expressed in rad/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, testFeatureSegment.cpp, testFrankaJointVelocityLimits.cpp, and testRobotFlirPtu.cpp.

Definition at line 261 of file vpRobot.cpp.

References vpRobot::maxRotationVelocity.

Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().

◆ 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 240 of file vpRobot.cpp.

References vpRobot::maxTranslationVelocity.

◆ setPosition() [1/3]

void vpRobotBiclops::setPosition ( const std::string &  filename)

Read the content of the position file and moves the head to joint positions.

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

Definition at line 521 of file vpRobotBiclops.cpp.

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

◆ setPosition() [2/3]

void vpRobotBiclops::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 positioning.
Parameters
frame: Control frame. This Biclops head can only be controlled in joint state.
q1: The pan joint position to set in radians.
q2: The tilt joint position to set in radians.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Definition at line 506 of file vpRobotBiclops.cpp.

References setPosition().

◆ setPosition() [3/3]

void vpRobotBiclops::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 positioning.
Parameters
frame: Control frame. This Biclops head can only be controlled in joint state.
q: The joint position to set for each axis in radians.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Examples
servoPioneerPanSegment3D.cpp.

Definition at line 468 of file vpRobotBiclops.cpp.

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

Referenced by setPosition().

◆ setPositioningVelocity()

void vpRobotBiclops::setPositioningVelocity ( double  velocity)

Set the velocity used for a position control.

Parameters
velocity: Velocity in % of the maximum velocity between [0,100]. The maximum velocity is given vpBiclops::speedLimit.

Definition at line 456 of file vpRobotBiclops.cpp.

References vpRobotException::constructionError.

◆ setRobotFrame()

vpRobot::vpControlFrameType vpRobot::setRobotFrame ( vpRobot::vpControlFrameType  newFrame)
protectedinherited

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotBiclops::setRobotState ( const 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
servoPioneerPanSegment3D.cpp.

Definition at line 383 of file vpRobotBiclops.cpp.

References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, stopMotion(), vpRobotBiclopsSpeedControlLoop(), and vpTime::wait().

Referenced by init(), setPosition(), and ~vpRobotBiclops().

◆ setVelocity()

void vpRobotBiclops::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector q_dot 
)
virtual

Send a velocity on each axis.

Parameters
frame: Control frame. This Biclops head can only be controlled in joint state. Be aware, the camera frame (vpRobot::CAMERA_FRAME), the reference frame (vpRobot::REFERENCE_FRAME), end-effector frame (vpRobot::END_EFFECTOR_FRAME) and the mixt frame (vpRobot::MIXT_FRAME) are not implemented.
q_dot: The desired joint velocities for each axis in rad/s. $ \dot {r} = [\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.
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 not supported frame type (vpRobot::CAMERA_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::END_EFFECTOR_FRAME or vpRobot::MIXT_FRAME) is given.
Warning
Velocities could be saturated if one of them exceed the maximal authorized speed (see vpRobot::maxRotationVelocity).

Implements vpRobot.

Examples
servoPioneerPanSegment3D.cpp.

Definition at line 594 of file vpRobotBiclops.cpp.

References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpBiclops::speedLimit, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.

◆ setVerbose()

◆ stopMotion()

void vpRobotBiclops::stopMotion ( void  )

Halt all the axis.

Definition at line 421 of file vpRobotBiclops.cpp.

References vpBiclops::ndof.

Referenced by setRobotState().

◆ vpRobotBiclopsSpeedControlLoop()

void vpRobotBiclops::vpRobotBiclopsSpeedControlLoop ( void *  arg)
static

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 114 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ defaultPositioningVelocity

BEGIN_VISP_NAMESPACE const double vpRobotBiclops::defaultPositioningVelocity = 10.0
static

Definition at line 94 of file vpRobotBiclops.h.

◆ eJe

◆ eJeAvailable

int vpRobot::eJeAvailable
protectedinherited

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

Definition at line 108 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ fJe

vpMatrix vpRobot::fJe
protectedinherited

◆ fJeAvailable

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 112 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ h

const float vpBiclops::h = 0.048f
staticinherited

Definition at line 104 of file vpBiclops.h.

Referenced by vpBiclops::set_cMe().

◆ m_cMe

vpHomogeneousMatrix vpBiclops::m_cMe
protectedinherited

Camera frame to PT end-effector frame transformation.

Definition at line 111 of file vpBiclops.h.

Referenced by vpBiclops::computeMGD(), vpBiclops::get_cVe(), vpBiclops::get_fMc(), and vpBiclops::set_cMe().

◆ m_dh_model

DenavitHartenbergModel vpBiclops::m_dh_model
protectedinherited

Denavit-Hartenberg model.

Definition at line 110 of file vpBiclops.h.

Referenced by vpBiclops::get_eJe(), vpBiclops::get_fJe(), vpBiclops::get_fMe(), and vpBiclops::init().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 101 of file vpRobot.h.

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

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

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

◆ ndof

BEGIN_VISP_NAMESPACE const unsigned int vpBiclops::ndof = 2
staticinherited

◆ nDof

◆ panJointLimit

const float vpBiclops::panJointLimit = (float)(M_PI)
staticinherited

Pan axis +/- joint limit in rad.

Definition at line 105 of file vpBiclops.h.

Referenced by vpRobotBiclopsSpeedControlLoop().

◆ qmax

double* vpRobot::qmax
protectedinherited

Definition at line 116 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ qmin

double* vpRobot::qmin
protectedinherited

Definition at line 115 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ speedLimit

const float vpBiclops::speedLimit = (float)(M_PI / 3.0)
staticinherited

Pan and tilt axis max velocity in rad/s to perform a displacement.

Definition at line 107 of file vpBiclops.h.

Referenced by setVelocity().

◆ tiltJointLimit

const float vpBiclops::tiltJointLimit = (float)(M_PI / 4.5)
staticinherited

Tilt axis +/- joint limit in rad.

Definition at line 106 of file vpBiclops.h.

Referenced by vpRobotBiclopsSpeedControlLoop().

◆ verbose_