Visual Servoing Platform
version 3.5.0 under development (2022-02-15)
|
#include <visp3/robot/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.
config.mk
to add -fPIC
build flag 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 112 of file vpRobotFlirPtu.cpp.
References emergencyStop(), and init().
|
virtual |
Destructor.
Definition at line 130 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 531 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 600 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 65 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 239 of file vpRobotFlirPtu.cpp.
References vpVelocityTwistMatrix::buildFrom(), vpHomogeneousMatrix::inverse(), and m_eMc.
|
virtual |
Get the robot Jacobian expressed in the end-effector frame.
[out] | eJe | : End-effector frame Jacobian. |
Implements vpRobot.
Definition at line 168 of file vpRobotFlirPtu.cpp.
References get_eJe().
vpMatrix vpRobotFlirPtu::get_eJe | ( | ) |
Get the robot Jacobian expressed in the end-effector frame.
Definition at line 149 of file vpRobotFlirPtu.cpp.
References vpRobot::eJe, getPosition(), vpRobot::JOINT_STATE, and vpArray2D< Type >::resize().
Referenced by 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 vpRobot::getDisplacement(), and vpRobot::getPosition().
|
virtual |
Get the robot Jacobian expressed in the robot reference frame.
[out] | fJe | : Base (or reference) frame Jacobian. |
Implements vpRobot.
Definition at line 196 of file vpRobotFlirPtu.cpp.
References get_fJe().
vpMatrix vpRobotFlirPtu::get_fJe | ( | ) |
Get the robot Jacobian expressed in the robot reference frame.
Definition at line 176 of file vpRobotFlirPtu.cpp.
References vpRobot::fJe, getPosition(), vpRobot::JOINT_STATE, and vpArray2D< Type >::resize().
Referenced by 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 202 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 518 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 412 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 613 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 273 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 251 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
std::string vpRobotFlirPtu::getNetworkGateway | ( | ) |
When connected to the PTU by serial, get the PTU network gateway.
Definition at line 886 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 906 of file vpRobotFlirPtu.cpp.
References vpMath::deg(), disconnect(), vpException::fatalError, m_cer, m_connected, m_res, m_status, and vpMath::rad().
std::string vpRobotFlirPtu::getNetworkIP | ( | ) |
When connected to the PTU by serial, get the PTU network IP address.
Definition at line 866 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 650 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 688 of file vpRobotFlirPtu.cpp.
References disconnect(), vpException::fatalError, m_connected, and m_vel_max_tics.
|
virtual |
Get robot position.
[in] | frame | : Considered cartesian frame or joint state. |
[out] | q | : Position of the arm. |
Implements vpRobot.
Definition at line 441 of file vpRobotFlirPtu.cpp.
References getJointPosition(), and vpRobot::JOINT_STATE.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 216 of file vpRobot.cpp.
References vpRobot::getPosition().
|
inlineprotectedinherited |
Definition at line 172 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 144 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotPtu46::setPosition(), vpRobotBiclops::setPosition(), vpSimulatorCamera::setPosition(), vpRobotCamera::setPosition(), vpSimulatorAfma6::setPosition(), vpRobotAfma4::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotTemplate::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotPtu46::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), stopMotion(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::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 669 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 97 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 832 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 163 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::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 vpRobot::init(), vpRobot::setPosition(), vpRobot::setRobotState(), and vpRobot::setVelocity().
|
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 259 of file vpRobotFlirPtu.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, vpRobot::JOINT_STATE, m_eMc, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpArray2D< Type >::size(), 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 321 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 260 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
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 239 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
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 707 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 455 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 767 of file vpRobotFlirPtu.cpp.
References m_positioning_velocity.
|
protectedinherited |
Definition at line 207 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::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 776 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 737 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 352 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 159 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotFlirPtu::stopMotion | ( | void | ) |
Stop PTU motion in velocity control mode.
Definition at line 846 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 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 104 of file vpRobot.h.
Referenced by get_eJe(), vpSimulatorCamera::get_eJe(), vpRobotCamera::get_eJe(), vpRobot::operator=(), vpRobotAfma4::setVelocity(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 106 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 108 of file vpRobot.h.
Referenced by get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protected |
Definition at line 162 of file vpRobotFlirPtu.h.
Referenced by connect(), disconnect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), reset(), setJointVelocity(), setPanPosLimits(), setPosition(), setRobotState(), setTiltPosLimits(), and stopMotion().
|
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(), and stopMotion().
|
protected |
Constant transformation between end-effector and tool (or camera) frame.
Definition at line 160 of file vpRobotFlirPtu.h.
Referenced by get_cVe(), and setCartVelocity().
|
protected |
Definition at line 169 of file vpRobotFlirPtu.h.
Referenced by setPosition().
|
protected |
Pan min/max position in robot tics unit.
Definition at line 164 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), and setPosition().
|
protected |
Tilt min/max position in robot tics unit.
Definition at line 165 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), and setPosition().
|
protected |
Definition at line 170 of file vpRobotFlirPtu.h.
Referenced by setPosition(), and setPositioningVelocity().
|
protected |
Pan/tilt tic resolution in deg.
Definition at line 167 of file vpRobotFlirPtu.h.
Referenced by getLimits(), and getNetworkHostName().
|
protected |
Definition at line 163 of file vpRobotFlirPtu.h.
Referenced by connect(), getJointPosition(), getLimits(), getNetworkGateway(), getNetworkHostName(), getNetworkIP(), reset(), setJointVelocity(), setPanPosLimits(), setPosition(), setRobotState(), setTiltPosLimits(), and stopMotion().
|
protected |
Pan/tilt max velocity in robot tics unit.
Definition at line 166 of file vpRobotFlirPtu.h.
Referenced by getLimits(), getPanTiltVelMax(), setJointVelocity(), and setPosition().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotTemplate::init(), init(), vpRobotKinova::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), init(), and vpRobotKinova::init().
|
protectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotTemplate::init(), init(), vpRobotKinova::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), init(), and vpRobotKinova::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 102 of file vpRobot.h.
Referenced by vpRobotKinova::getJointPosition(), vpRobotTemplate::init(), init(), vpRobotKinova::init(), vpRobot::operator=(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotTemplate::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpRobotCamera::vpRobotCamera(), vpRobotFranka::vpRobotFranka(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().