![]() |
Visual Servoing Platform version 3.7.0
|
#include <vpRobotFlirPtu.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 void | emergencyStop (int signo) |
Static Public Member Functions inherited from vpRobot | |
| static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Protected Member Functions | |
| void | init () |
| void | getLimits () |
| void | getJointPosition (vpColVector &q) |
| void | setCartVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &v) |
| void | setJointVelocity (const vpColVector &qdot) |
Protected Member Functions Inherited from vpRobot | |
| vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
| vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
| vpHomogeneousMatrix | m_eMc |
| struct cerial * | m_cer |
| uint16_t | m_status |
| std::vector< int > | m_pos_max_tics |
| std::vector< int > | m_pos_min_tics |
| std::vector< int > | m_vel_max_tics |
| std::vector< double > | m_res |
| bool | m_connected |
| int | m_njoints |
| double | m_positioning_velocity |
| 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 FLIR pan-tilt units compatible with FLIR PTU-SDK.
Tutorials
If you are interested in using performing visual servoing using a FLIR pan-tilt unit, you may have a look at:
Definition at line 96 of file vpRobotFlirPtu.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.
| vpRobotFlirPtu::vpRobotFlirPtu | ( | ) |
Default constructor.
Definition at line 108 of file vpRobotFlirPtu.cpp.
References emergencyStop(), init(), m_cer, m_connected, m_eMc, m_njoints, m_pos_max_tics, m_pos_min_tics, m_positioning_velocity, m_res, m_status, and m_vel_max_tics.
|
virtual |
Destructor.
Definition at line 126 of file vpRobotFlirPtu.cpp.
References disconnect(), and stopMotion().
| void vpRobotFlirPtu::connect | ( | const std::string & | portname, |
| int | baudrate = 9600 ) |
Connect to FLIR PTU.
| [in] | portname | : Connect to serial/socket. |
| [in] | baudrate | : Use baud rate (default: 9600). |
Definition at line 528 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, getLimits(), m_cer, m_connected, and m_status.
| void vpRobotFlirPtu::disconnect | ( | ) |
Close connection to PTU.
Definition at line 597 of file vpRobotFlirPtu.cpp.
References m_cer, and m_connected.
Referenced by connect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), getPanPosLimits(), getPanTiltVelMax(), getTiltPosLimits(), setJointVelocity(), setPanPosLimits(), setPosition(), setTiltPosLimits(), and ~vpRobotFlirPtu().
|
static |
Emergency stops the robot if the program is interrupted by a SIGINT (CTRL C), SIGSEGV (segmentation fault), SIGBUS (bus error), SIGKILL or SIGQUIT signal.
Definition at line 61 of file vpRobotFlirPtu.cpp.
References vpRobotException::signalException.
Referenced by vpRobotFlirPtu().
| vpVelocityTwistMatrix vpRobotFlirPtu::get_cVe | ( | ) | const |
Return the velocity twist transformation matrix from camera frame to end-effector frame. This transformation allows to transform a velocity twist expressed in the end-effector frame into the camera frame thanks to the homogeneous matrix eMc set using set_eMc().
Definition at line 235 of file vpRobotFlirPtu.cpp.
References vpVelocityTwistMatrix::buildFrom(), and m_eMc.
| vpMatrix vpRobotFlirPtu::get_eJe | ( | ) |
Get the robot Jacobian expressed in the end-effector frame.
Definition at line 145 of file vpRobotFlirPtu.cpp.
References vpRobot::eJe, getPosition(), and vpRobot::JOINT_STATE.
Referenced by get_eJe().
|
virtual |
Get the robot Jacobian expressed in the end-effector frame.
| [out] | eJe | : End-effector frame Jacobian. |
Implements vpRobot.
Definition at line 164 of file vpRobotFlirPtu.cpp.
References vpRobot::eJe, and get_eJe().
|
inline |
Return constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.
Definition at line 115 of file vpRobotFlirPtu.h.
References m_eMc.
| vpMatrix vpRobotFlirPtu::get_fJe | ( | ) |
Get the robot Jacobian expressed in the robot reference frame.
Definition at line 172 of file vpRobotFlirPtu.cpp.
References vpRobot::fJe, getPosition(), and vpRobot::JOINT_STATE.
Referenced by get_fJe().
|
virtual |
Get the robot Jacobian expressed in the robot reference frame.
| [out] | fJe | : Base (or reference) frame Jacobian. |
Implements vpRobot.
Definition at line 192 of file vpRobotFlirPtu.cpp.
References vpRobot::fJe, and get_fJe().
| vpMatrix vpRobotFlirPtu::get_fMe | ( | ) |
Get the robot geometric model corresponding to the homogeneous transformation between base (or reference) frame and end-effector frame.
Definition at line 198 of file vpRobotFlirPtu.cpp.
References getPosition(), and vpRobot::JOINT_STATE.
|
virtual |
Get a displacement.
| [in] | frame | : Considered cartesian frame or joint state. |
| [out] | q | : Displacement in meter and rad. |
Implements vpRobot.
Definition at line 515 of file vpRobotFlirPtu.cpp.
|
protected |
Get robot joint positions.
| [in] | q | : Joint position as a 2-dim vector [pan, tilt] with values in radians. |
Definition at line 408 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and vpColVector::resize().
Referenced by getPosition().
|
protected |
Read min/max position and speed.
Definition at line 610 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, m_pos_max_tics, m_pos_min_tics, m_res, m_status, and m_vel_max_tics.
Referenced by connect().
|
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 |
| std::string vpRobotFlirPtu::getNetworkGateway | ( | ) |
When connected to the PTU by serial, get the PTU network gateway.
Definition at line 884 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, and m_status.
| std::string vpRobotFlirPtu::getNetworkHostName | ( | ) |
When connected to the PTU, get the PTU network hostname.
Definition at line 904 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, and m_status.
| std::string vpRobotFlirPtu::getNetworkIP | ( | ) |
When connected to the PTU by serial, get the PTU network IP address.
Definition at line 864 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, and m_status.
| vpColVector vpRobotFlirPtu::getPanPosLimits | ( | ) |
Return pan axis min and max position limits in radians as a 2-dim vector, with first value the pan min position and second value, the pan max position.
Definition at line 647 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_connected, m_pos_max_tics, and m_pos_min_tics.
| vpColVector vpRobotFlirPtu::getPanTiltVelMax | ( | ) |
Return pan/tilt axis max velocity in rad/s as a 2-dim vector, with first value the pan max velocity and second value, the max tilt velocity.
Definition at line 685 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_connected, and m_vel_max_tics.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 215 of file vpRobot.cpp.
References getPosition().
|
virtual |
Get robot position.
| [in] | frame | : Considered cartesian frame or joint state. |
| [out] | q | : Position of the arm. |
Implements vpRobot.
Definition at line 437 of file vpRobotFlirPtu.cpp.
References getJointPosition(), and vpRobot::JOINT_STATE.
|
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 vpRobotFlirPtu::getTiltPosLimits | ( | ) |
Return tilt axis min and max position limits in radians as a 2-dim vector, with first value the tilt min position and second value, the tilt max position.
Definition at line 666 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_connected, m_pos_max_tics, and m_pos_min_tics.
|
protectedvirtual |
Basic initialization.
Implements vpRobot.
Definition at line 93 of file vpRobotFlirPtu.cpp.
References vpRobot::maxRotationVelocity, vpRobot::maxRotationVelocityDefault, vpRobot::maxTranslationVelocity, vpRobot::maxTranslationVelocityDefault, and vpRobot::nDof.
Referenced by vpRobotFlirPtu().
| void vpRobotFlirPtu::reset | ( | ) |
Reset PTU axis.
Definition at line 830 of file vpRobotFlirPtu.cpp.
References vpException::fatalError, m_cer, m_connected, and m_status.
|
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().
|
inline |
Set constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.
Definition at line 135 of file vpRobotFlirPtu.h.
References m_eMc.
|
protected |
Send to the controller a 6-dim velocity skew vector expressed in a Cartesian frame.
| [in] | frame | : Cartesian control frame (either tool frame or end-effector) in which the velocity v is expressed. Units are m/s for translation and rad/s for rotation velocities. |
| [in] | v | : 6-dim vector that contains the 6 components of the velocity skew to send to the robot. Units are m/s and rad/s. |
Definition at line 255 of file vpRobotFlirPtu.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, vpRobot::JOINT_STATE, m_eMc, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpRobot::TOOL_FRAME.
Referenced by setVelocity().
|
protected |
Send a joint velocity to the controller.
| [in] | qdot | : Joint velocities vector. Units are rad/s for a robot arm. |
Definition at line 317 of file vpRobotFlirPtu.cpp.
References vpMath::deg(), disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and m_vel_max_tics.
Referenced by 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 vpRobotFlirPtu::setPanPosLimits | ( | const vpColVector & | pan_limits | ) |
Modify pan position limit.
| pan_limits | : 2-dim vector that contains pan min and max limits in rad. |
Definition at line 704 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and vpArray2D< Type >::size().
|
virtual |
Set a position to reach.
| [in] | frame | : Considered cartesian frame or joint state. |
| [in] | q | : Position to reach. |
Implements vpRobot.
Definition at line 452 of file vpRobotFlirPtu.cpp.
References vpMath::deg(), disconnect(), vpException::fatalError, vpRobot::JOINT_STATE, m_cer, m_connected, m_njoints, m_pos_max_tics, m_pos_min_tics, m_positioning_velocity, m_status, m_vel_max_tics, and vpArray2D< Type >::size().
| void vpRobotFlirPtu::setPositioningVelocity | ( | double | velocity | ) |
Set the velocity used for a position control.
| velocity | : Velocity in % of the maximum velocity between [0, 100]. Default value is 20. |
Definition at line 764 of file vpRobotFlirPtu.cpp.
References m_positioning_velocity.
|
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 robot state.
| newState | : New requested robot state if the robot is connected. If the robot is not connected, we return the current state. |
Reimplemented from vpRobot.
Definition at line 773 of file vpRobotFlirPtu.cpp.
References vpException::fatalError, vpRobot::getRobotState(), m_cer, m_connected, m_status, vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and stopMotion().
| void vpRobotFlirPtu::setTiltPosLimits | ( | const vpColVector & | tilt_limits | ) |
Modify tilt position limit.
| tilt_limits | : 2-dim vector that contains tilt min and max limits in rad. |
Definition at line 734 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and vpArray2D< Type >::size().
|
virtual |
Send to the controller a velocity in a given frame.
| [in] | frame | : Control frame in which the velocity vel is expressed. Velocities could be joint velocities, or cartesian velocities. Units are m/s for translation and rad/s for rotation velocities. |
| [in] | vel | : Vector that contains the velocity to apply to the robot. |
Implements vpRobot.
Definition at line 348 of file vpRobotFlirPtu.cpp.
References vpException::dimensionError, vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::nDof, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), setCartVelocity(), setJointVelocity(), vpArray2D< Type >::size(), vpRobot::STATE_VELOCITY_CONTROL, vpRobot::TOOL_FRAME, and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 167 of file vpRobot.h.
References verbose_.
Referenced by vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
| void vpRobotFlirPtu::stopMotion | ( | ) |
Stop PTU motion in velocity control mode.
Definition at line 844 of file vpRobotFlirPtu.cpp.
References vpException::fatalError, vpRobot::getRobotState(), m_cer, m_connected, m_status, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by setRobotState(), and ~vpRobotFlirPtu().
|
protectedinherited |
Definition at line 111 of file vpRobot.h.
Referenced by operator=(), vpRobot(), and vpRobot().
|
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().
|
protected |
Definition at line 162 of file vpRobotFlirPtu.h.
Referenced by connect(), disconnect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), reset(), setJointVelocity(), setPanPosLimits(), setPosition(), setRobotState(), setTiltPosLimits(), stopMotion(), and vpRobotFlirPtu().
|
protected |
Definition at line 168 of file vpRobotFlirPtu.h.
Referenced by connect(), disconnect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), getPanPosLimits(), getPanTiltVelMax(), getTiltPosLimits(), reset(), setJointVelocity(), setPanPosLimits(), setPosition(), setRobotState(), setTiltPosLimits(), stopMotion(), and vpRobotFlirPtu().
|
protected |
Constant transformation between end-effector and tool (or camera) frame.
Definition at line 160 of file vpRobotFlirPtu.h.
Referenced by get_cVe(), get_eMc(), set_eMc(), setCartVelocity(), and vpRobotFlirPtu().
|
protected |
Definition at line 169 of file vpRobotFlirPtu.h.
Referenced by setPosition(), and vpRobotFlirPtu().
|
protected |
Pan min/max position in robot tics unit.
Definition at line 164 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), setPosition(), and vpRobotFlirPtu().
|
protected |
Tilt min/max position in robot tics unit.
Definition at line 165 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), setPosition(), and vpRobotFlirPtu().
|
protected |
Definition at line 170 of file vpRobotFlirPtu.h.
Referenced by setPosition(), setPositioningVelocity(), and vpRobotFlirPtu().
|
protected |
Pan/tilt tic resolution in deg.
Definition at line 167 of file vpRobotFlirPtu.h.
Referenced by getLimits(), and vpRobotFlirPtu().
|
protected |
Definition at line 163 of file vpRobotFlirPtu.h.
Referenced by connect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), reset(), setJointVelocity(), setPanPosLimits(), setPosition(), setRobotState(), setTiltPosLimits(), stopMotion(), and vpRobotFlirPtu().
|
protected |
Pan/tilt max velocity in robot tics unit.
Definition at line 166 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanTiltVelMax(), setJointVelocity(), setPosition(), and vpRobotFlirPtu().
|
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().
|
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().