Visual Servoing Platform  version 3.6.1 under development (2024-10-01)

#include <visp3/robot/vpRobotCamera.h>

+ Inheritance diagram for vpRobotCamera:

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

 vpRobotCamera ()
 
Inherited functionalities from vpRobotSimulator
double getSamplingTime () const
 
virtual void setSamplingTime (const double &delta_t)
 
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)
 
virtual vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState)
 
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)
 

Protected Member Functions

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

Protected Attributes

vpHomogeneousMatrix cMw_
 
double delta_t_
 
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
 

Inherited functionalities from vpRobotCamera

void get_cVe (vpVelocityTwistMatrix &cVe) const
 
void get_eJe (vpMatrix &eJe) VP_OVERRIDE
 
void getPosition (vpHomogeneousMatrix &cMw) const
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
 
void setPosition (const vpHomogeneousMatrix &cMw)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &v) VP_OVERRIDE
 

Detailed Description

Class that defines the simplest robot: a free flying camera. We recommend to use vpSimulatorCamera instead.

Deprecated:
This class is deprecated since ViSP 3.0.0.

This free flying camera has 6 dof; 3 in translation and 3 in rotation. It evolves as a gantry robot with respect to a world frame. This class is similar to vpSimulatorCamera class except that here the position of the robot is provided as the transformation from camera frame to world frame; cMw. Since the position of the camera frame evolves, this representation is less intuitive than the one implemented in vpSimulatorCamera where the transformation from world to camera frame is considered; wMc.

For this particular simulated robot, the end-effector and camera frame are confused. That means that the cMe transformation is equal to identity.

The robot jacobian expressed in the end-effector frame $ {^e}{\bf J}_e $ is also set to identity (see get_eJe()).

The following code shows how to control this robot in position and velocity.

#include <visp3/robot/vpRobotCamera.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
robot.getPosition(cMw); // Position of the world frame in the camera frame
std::cout << "Default position of the world frame in the camera frame cMw:\n" << cMw << std::endl;
cMw[2][3] = 1.; // World frame is 1 meter along z axis in front of the camera frame
robot.setPosition(cMw); // Set the new position of the world frame in the camera frame
std::cout << "New position of the world frame in the camera frame cMw:\n" << cMw << std::endl;
robot.setSamplingTime(0.100); // Modify the default sampling time to 0.1 second
robot.setMaxTranslationVelocity(1.); // vx, vy and vz max set to 1 m/s
robot.setMaxRotationVelocity(vpMath::rad(90)); // wx, wy and wz max set to 90 deg/s
v = 0;
v[2] = 1.; // set v_z to 1 m/s
// The robot has moved from 0.1 meters along the z axis
robot.getPosition(cMw); // Position of the world frame in the camera frame
std::cout << "New position of the camera cMw:\n" << cMw << std::endl;
}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
Implementation of an homogeneous matrix and operations on such kind of matrices.
static double rad(double deg)
Definition: vpMath.h:129
Class that defines the simplest robot: a free flying camera. We recommend to use vpSimulatorCamera in...
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ CAMERA_FRAME
Definition: vpRobot.h:84
void setMaxRotationVelocity(double maxVr)
Definition: vpRobot.cpp:261
void setMaxTranslationVelocity(double maxVt)
Definition: vpRobot.cpp:240

Definition at line 112 of file vpRobotCamera.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 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

◆ vpRobotCamera()

BEGIN_VISP_NAMESPACE vpRobotCamera::vpRobotCamera ( )

Constructor.

Initialise the robot by a call to init().

Sampling time is set to 40 ms. To change it you should call setSamplingTime().

Robot jacobian expressed in the end-effector frame $ {^e}{\bf J}_e $ is set to identity (see get_eJe()).

robot.setSamplingTime(0.020); // Set the sampling time to 20 ms.

Definition at line 70 of file vpRobotCamera.cpp.

Member Function Documentation

◆ get_cVe()

void vpRobotCamera::get_cVe ( vpVelocityTwistMatrix cVe) const

Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.

Parameters
cVe: Twist transformation. Here this transformation is equal to identity since camera frame and end-effector frame are at the same location.

Definition at line 103 of file vpRobotCamera.cpp.

◆ get_eJe()

void vpRobotCamera::get_eJe ( vpMatrix eJe_)
virtual

Get the robot jacobian expressed in the end-effector frame. For that simple robot the Jacobian is the identity.

Parameters
eJe_: A 6 by 6 matrix representing the robot jacobian $ {^e}{\bf J}_e$ expressed in the end-effector frame.

Implements vpRobot.

Definition at line 116 of file vpRobotCamera.cpp.

References vpRobot::eJe.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

◆ 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/3]

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/3]

void vpRobotCamera::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector position 
)
virtual

◆ getPosition() [3/3]

void vpRobotCamera::getPosition ( vpHomogeneousMatrix cMw) const

Get the robot position as the transformation from camera frame to world frame.

Definition at line 181 of file vpRobotCamera.cpp.

References cMw_.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

◆ getRobotState()

virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtualinherited

Definition at line 155 of file vpRobot.h.

Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), setPosition(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpSimulatorAfma6::setPosition(), vpSimulatorViper850::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), vpRobotViper850::stopMotion(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().

◆ getSamplingTime()

double vpRobotSimulator::getSamplingTime ( ) const
inlineinherited

Return the sampling time.

Returns
Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

Definition at line 73 of file vpRobotSimulator.h.

Referenced by vpSimulatorAfma6::updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().

◆ 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 setVelocity(), 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().

◆ 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(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().

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

Referenced by vpSimulatorAfma6::setPosition().

◆ setPosition()

void vpRobotCamera::setPosition ( const vpHomogeneousMatrix cMw)

Set the robot position as the transformation from camera frame to world frame.

Definition at line 242 of file vpRobotCamera.cpp.

References cMw_, vpRobot::getRobotState(), vpRobot::setRobotState(), and vpRobot::STATE_POSITION_CONTROL.

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobot::setRobotState ( const vpRobot::vpRobotStateType  newState)
virtualinherited

Reimplemented in vpRobotViper850, vpRobotViper650, vpRobotUniversalRobots, vpRobotPtu46, vpRobotFranka, vpRobotFlirPtu, vpRobotAfma6, vpRobotAfma4, vpSimulatorViper850, vpSimulatorAfma6, vpRobotPololuPtu, and vpRobotBiclops.

Examples
UniversalRobotsMoveToPosition.cpp, UniversalRobotsSavePosition.cpp, frankaMoveToPosition.cpp, frankaSavePosition.cpp, moveAfma4.cpp, moveBiclops.cpp, movePtu46.cpp, photometricMappingVisualServoing.cpp, photometricVisualServoing.cpp, photometricVisualServoingWithoutVpServo.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoKinovaJacoCart.cpp, servoKinovaJacoJoint.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, testFrankaCartForceTorque-2.cpp, testFrankaCartForceTorque.cpp, testFrankaCartVelocity-2.cpp, testFrankaCartVelocity-3.cpp, testFrankaCartVelocity.cpp, testFrankaJointPosition.cpp, testFrankaJointTorque.cpp, testFrankaJointVelocity-2.cpp, testFrankaJointVelocity-3.cpp, testFrankaJointVelocity.cpp, testFrankaJointVelocityLimits.cpp, testRobotFlirPtu.cpp, testRobotViper650-frames.cpp, testRobotViper850-frames.cpp, testUniversalRobotsCartPosition.cpp, testUniversalRobotsCartVelocity.cpp, testUniversalRobotsJointPosition.cpp, testUniversalRobotsJointVelocity.cpp, testVirtuoseAfma6.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, and tutorial-ibvs-4pts-wireframe-robot-viper.cpp.

Definition at line 202 of file vpRobot.cpp.

Referenced by setPosition(), vpSimulatorCamera::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().

◆ setSamplingTime()

virtual void vpRobotSimulator::setSamplingTime ( const double &  delta_t)
inlinevirtualinherited

Set the sampling time.

Parameters
delta_t: Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

Reimplemented in vpRobotWireFrameSimulator.

Definition at line 81 of file vpRobotSimulator.h.

◆ setVelocity()

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

Send to the controller a velocity.

Parameters
frame: Control frame type. Only articular (vpRobot::ARTICULAR_FRAME) and camera frame (vpRobot::CAMERA_FRAME) are implemented.
v: Velocity twist to apply to the robot.
  • In the camera frame, this velocity is represented by a twist vector of dimension 6 $ {\bf v} = [v_x v_y v_z w_x w_y w_z]^t $ where $ v_x, v_y, v_z $ are the translation velocities in m/s and $ w_x, w_y, w_z $ the rotation velocities in rad/s applied in the camera frame.
  • In articular, the behavior is the same as in camera frame.

Internally, the exponential map (vpExponentialMap) is used to update the camera position from its velocity after applying the velocity during a sampling time. This sampling time can be set using setSamplingTime().

See also
setSamplingTime()

Implements vpRobot.

Definition at line 140 of file vpRobotCamera.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, cMw_, vpRobotSimulator::delta_t_, vpExponentialMap::direct(), vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpHomogeneousMatrix::inverse(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::setRobotState(), vpRobot::STATE_VELOCITY_CONTROL, and vpRobotException::wrongStateError.

◆ setVerbose()

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 114 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ cMw_

vpHomogeneousMatrix vpRobotCamera::cMw_
protected

Definition at line 115 of file vpRobotCamera.h.

Referenced by getPosition(), setPosition(), and setVelocity().

◆ delta_t_

double vpRobotSimulator::delta_t_
protectedinherited

◆ 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

◆ 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=().

◆ 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

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

◆ verbose_