![]() |
Visual Servoing Platform version 3.7.0
|
#include <vpRobotPtu46.h>
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 } |
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 |
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.
Definition at line 75 of file vpRobotPtu46.h.
|
inherited |
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. |
|
inherited |
Robot control states.
| vpRobotPtu46::vpRobotPtu46 | ( | const std::string & | device = "/dev/ttyS0" | ) |
Default constructor.
Initialize the ptu-46 pan, tilt head by opening the serial port.
Definition at line 68 of file vpRobotPtu46.cpp.
References defaultPositioningVelocity, init(), setRobotState(), vpRobot::STATE_STOP, vpDEBUG_TRACE, vpERROR_TRACE, and vpRobot::vpRobot().
| VP_EXPLICIT vpRobotPtu46::vpRobotPtu46 | ( | vpRobotPtu46 * | pub | ) |
References getPositioningVelocity(), getVelocity(), readPositionFile(), setPositioningVelocity(), and stopMotion().
|
virtual |
Destructor. Close the serial connection with the head.
Definition at line 102 of file vpRobotPtu46.cpp.
References setRobotState(), vpRobot::STATE_STOP, and vpERROR_TRACE.
|
inherited |
Return the direct geometric model of the camera: fMc
| q | : Articular position for pan and tilt axis. |
Definition at line 116 of file vpPtu46.cpp.
References computeMGD().
|
inherited |
Compute the direct geometric model of the camera: fMc
| 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 66 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), h, L, vpCDEBUG, and vpERROR_TRACE.
Referenced by computeMGD(), and computeMGD().
|
inherited |
Compute the direct geometric model of the camera in terms of pose vector.
| 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 134 of file vpPtu46.cpp.
References computeMGD(), and vpHomogeneousMatrix::inverse().
| 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.
| cMe | : Homogeneous matrix between camera and end effector frame. |
Definition at line 220 of file vpRobotPtu46.cpp.
References vpPtu46::get_cMe().
| 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.
| cVe | : Twist transformation between camera and end effector frame to express a velocity skew from end effector frame in camera frame. |
Definition at line 203 of file vpRobotPtu46.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpPtu46::get_cMe().
|
inherited |
Get the robot jacobian expressed in the end-effector frame.
| q | : Articular position for pan and tilt axis. |
| eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Definition at line 245 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.
Referenced by vpRobotPtu46::get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame.
| eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 232 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::eJe, vpPtu46::get_eJe(), getPosition(), and vpERROR_TRACE.
|
inherited |
Get the robot jacobian expressed in the robot reference frame
| 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 274 of file vpPtu46.cpp.
References vpException::dimensionError, vpArray2D< Type >::getRows(), vpArray2D< Type >::resize(), and vpERROR_TRACE.
Referenced by vpRobotPtu46::get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame
| fJe | : Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 253 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::fJe, vpPtu46::get_fJe(), getPosition(), and vpERROR_TRACE.
|
virtual |
Get the robot displacement since the last call of this method.
| frame | The frame in which the measured displacement is expressed. |
| d | The displacement:
|
| vpRobotException::wrongStateError | If a not supported frame type is given. |
Implements vpRobot.
Definition at line 733 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, and vpRobotException::wrongStateError.
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 272 of file vpRobot.cpp.
References maxRotationVelocity.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), getDisplacement(), vpRobotPololuPtu::setPosition(), vpSimulatorAfma6::setPosition(), vpRobotAfma6::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), and vpSimulatorViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 250 of file vpRobot.cpp.
References maxTranslationVelocity.
Referenced by getDisplacement(), vpSimulatorAfma6::setPosition(), vpRobotAfma6::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), and vpSimulatorViper850::setVelocity().
|
inlineinherited |
|
inherited |
Return the current robot position in the specified frame.
Definition at line 215 of file vpRobot.cpp.
References getPosition().
|
virtual |
Return the position of each axis.
| frame | : Control frame. This head can only be controlled in articular. |
| q | : The position of the axis. |
| vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 409 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.
| double vpRobotPtu46::getPositioningVelocity | ( | void | ) |
Get the velocity in % used for a position control.
Definition at line 280 of file vpRobotPtu46.cpp.
Referenced by vpRobotPtu46().
|
inlineprotectedinherited |
Definition at line 180 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 152 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotAfma6::setPosition(), vpRobotBiclops::setPosition(), vpRobotCamera::setPosition(), vpRobotFranka::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpSimulatorAfma6::setPosition(), vpSimulatorCamera::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma6::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), vpRobotViper850::stopMotion(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().
| vpColVector vpRobotPtu46::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Return the articular velocity.
| frame | : Control frame. This head can only be controlled in articular. |
| vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 629 of file vpRobotPtu46.cpp.
References getVelocity().
| void vpRobotPtu46::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
| vpColVector & | q_dot ) |
Get the articular velocity.
| frame | : Control frame. This head can only be controlled in articular. |
| q_dot | : The measured articular velocity in rad/s. |
| vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 581 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(), and vpRobotPtu46().
|
virtual |
Open the serial port.
| vpRobotException::constructionError | : If the device cannot be opened. |
Implements vpRobot.
Definition at line 132 of file vpRobotPtu46.cpp.
References vpRobotException::constructionError, vpDEBUG_TRACE, and vpERROR_TRACE.
Referenced by vpRobotPtu46().
| bool vpRobotPtu46::readPositionFile | ( | const std::string & | filename, |
| vpColVector & | q ) |
Get an articular position from the position file.
| filename | : Position file. |
| q | : The articular position read in the file. |
Definition at line 656 of file vpRobotPtu46.cpp.
References vpColVector::deg2rad(), vpPtu46::ndof, vpColVector::resize(), and vpIoTools::splitChain().
Referenced by setPosition(), and vpRobotPtu46().
|
staticinherited |
Saturate velocities.
| 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. |
| 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.
Definition at line 162 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotAfma6::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
| w_max | : Maximum rotational velocity expressed in rad/s. |
Definition at line 259 of file vpRobot.cpp.
References maxRotationVelocity.
Referenced by init(), vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
| v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 238 of file vpRobot.cpp.
References maxTranslationVelocity.
Referenced by init(), and vpSimulatorAfma6::setPosition().
| void vpRobotPtu46::setPosition | ( | const char * | filename | ) |
Read the content of the position file and moves to head to articular position.
| filename | : Position filename |
| vpRobotException::readingParametersError | : If the articular position cannot be read from file. |
Definition at line 386 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::readingParametersError, readPositionFile(), setPosition(), and vpERROR_TRACE.
| void vpRobotPtu46::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
| const double & | q1, | ||
| const double & | q2 ) |
Move the robot in position control.
| frame | : Control frame. This head can only be controlled in articular. |
| q1 | : The pan position to set. |
| q2 | : The tilt position to set. |
| vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 358 of file vpRobotPtu46.cpp.
References setPosition(), and vpERROR_TRACE.
|
virtual |
Move the robot in position control.
| frame | : Control frame. This head can only be controlled in articular. |
| q | : The position to set for each axis. |
| vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 298 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(), and setPosition().
| void vpRobotPtu46::setPositioningVelocity | ( | double | velocity | ) |
Set the velocity used for a position control.
| velocity | : Velocity in % of the maximum velocity between [0,100]. |
Definition at line 273 of file vpRobotPtu46.cpp.
Referenced by vpRobotPtu46().
|
protectedinherited |
Definition at line 206 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorAfma6::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtual |
Change the state of the robot either to stop them, or to set position or speed control.
Reimplemented from vpRobot.
Definition at line 149 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().
|
virtual |
Send a velocity on each axis.
| 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. |
| 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. |
Implements vpRobot.
Definition at line 477 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::maxRotationVelocity, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::STATE_VELOCITY_CONTROL, vpCDEBUG, vpDEBUG_TRACE, vpERROR_TRACE, and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 167 of file vpRobot.h.
References verbose_.
Referenced by vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
| void vpRobotPtu46::stopMotion | ( | void | ) |
Halt all the axis.
Definition at line 187 of file vpRobotPtu46.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
Referenced by vpRobotPtu46().
|
protectedinherited |
Definition at line 111 of file vpRobot.h.
Referenced by operator=(), vpRobot(), and vpRobot().
|
static |
Definition at line 92 of file vpRobotPtu46.h.
Referenced by vpRobotPtu46().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 103 of file vpRobot.h.
Referenced by vpRobotAfma6::get_eJe(), vpRobotBiclops::get_eJe(), vpRobotCamera::get_eJe(), vpRobotFlirPtu::get_eJe(), vpRobotFlirPtu::get_eJe(), vpRobotKinova::get_eJe(), vpRobotPioneer::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpSimulatorCamera::get_eJe(), operator=(), vpRobot(), and vpRobot().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 105 of file vpRobot.h.
Referenced by operator=(), vpRobot(), and vpRobot().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 107 of file vpRobot.h.
Referenced by vpRobotAfma6::get_fJe(), vpRobotBiclops::get_fJe(), vpRobotFlirPtu::get_fJe(), vpRobotFlirPtu::get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), operator=(), vpRobot(), and vpRobot().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 109 of file vpRobot.h.
Referenced by operator=(), vpRobot(), and vpRobot().
|
staticinherited |
Horizontal offset along the last joint, from last joint to camera frame. Vertical offset from last joint to camera frame.
Definition at line 78 of file vpPtu46.h.
Referenced by computeMGD(), get_cMe(), and operator<<.
|
staticinherited |
Geometric model
Definition at line 77 of file vpPtu46.h.
Referenced by computeMGD(), get_cMe(), and operator<<.
|
protectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), operator=(), setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobot(), vpRobot(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot(), and vpRobot().
|
protectedinherited |
Definition at line 95 of file vpRobot.h.
Referenced by getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), operator=(), setMaxTranslationVelocity(), vpRobot(), and vpRobot().
|
staticprotectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot(), and vpRobot().
|
protectedinherited |
number of degrees of freedom
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), getNDof(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobotUniversalRobots::init(), operator=(), vpRobotUniversalRobots::readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotTemplate::setVelocity(), vpRobot(), vpRobot(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
staticinherited |
Nombre d'articulations du robot. Number of dof
Pan and tilt are considered.
Definition at line 74 of file vpPtu46.h.
Referenced by vpRobotPtu46::getDisplacement(), vpRobotPtu46::getPosition(), vpRobotPtu46::getVelocity(), and vpRobotPtu46::readPositionFile().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by operator=(), vpRobot(), vpRobot(), and ~vpRobot().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by operator=(), vpRobot(), vpRobot(), and ~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpSimulatorAfma6::initialiseCameraRelativeToObject(), vpSimulatorViper850::initialiseCameraRelativeToObject(), operator=(), vpSimulatorAfma6::setPosition(), vpSimulatorViper850::setPosition(), setVerbose(), vpRobotWireFrameSimulator::setVerbose(), vpSimulatorAfma6::updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), vpRobot(), vpRobot(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().