Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
vpRobotFlirPtu Class Reference

#include <visp3/robot/vpRobotFlirPtu.h>

+ Inheritance diagram for vpRobotFlirPtu:

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

 vpRobotFlirPtu ()
 
virtual ~vpRobotFlirPtu ()
 
void connect (const std::string &portname, int baudrate=9600)
 
void disconnect ()
 
void get_eJe (vpMatrix &eJe)
 
vpMatrix get_eJe ()
 
void get_fJe (vpMatrix &fJe)
 
vpMatrix get_fJe ()
 
vpMatrix get_fMe ()
 
vpHomogeneousMatrix get_eMc () const
 
vpVelocityTwistMatrix get_cVe () const
 
void getDisplacement (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
std::string getNetworkIP ()
 
std::string getNetworkGateway ()
 
std::string getNetworkHostName ()
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
vpColVector getPanPosLimits ()
 
vpColVector getTiltPosLimits ()
 
vpColVector getPanTiltVelMax ()
 
void reset ()
 
void set_eMc (vpHomogeneousMatrix &eMc)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q)
 
void setPanPosLimits (const vpColVector &pan_limits)
 
void setTiltPosLimits (const vpColVector &tilt_limits)
 
void setPositioningVelocity (double velocity)
 
vpRobot::vpRobotStateType setRobotState (vpRobot::vpRobotStateType newState)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void stopMotion ()
 
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxRotationVelocity (double maxVr)
 
void setMaxTranslationVelocity (double maxVt)
 
void setVerbose (bool verbose)
 

Static Public Member Functions

static void 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
 

Detailed Description

Interface for FLIR pan-tilt units compatible with FLIR PTU-SDK.

Note
We strongly recommend to communicate with the PTU using network interface. We experienced communication issues using serial communication.
Warning
On Unix-like OS, if you experienced the following error when running servoFlirPtu.cpp:
Failed to open /dev/ttyUSB0: Permission denied.
  1. Add users to the "dialout" group:
    $ sudo adduser <username> dialout
  2. Reboot
Again on Unix-like OS, if you experienced the following error during ViSP build:
<your path>/sdk-x.y.z/libcpi.a(cerial.o): relocation R_X86_64_PC32 against symbol `serposix' can not be used when
making a shared object; recompile with -fPIC
  1. Enter FLIR PTU SDK folder and modify config.mk to add -fPIC build flag
    $ cat <your path>/sdk-x.y.y/config.mk
    CFLAGS=-g -Wall -Werror -DLITTLE_ENDIAN -O2 -fPIC
  2. Rebuild PTU-SDK
    $ cd <your path>/sdk-x.y.y
    $ make clean
    $ make
  3. Rebuild ViSP
    $ cd $VISP_WS/visp-build
    $ make -j4
See also
Tutorial: Visual servoing with FLIR Pan Tilt Unit
Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 96 of file vpRobotFlirPtu.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 75 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

◆ vpRobotFlirPtu()

vpRobotFlirPtu::vpRobotFlirPtu ( )

Default constructor.

Definition at line 112 of file vpRobotFlirPtu.cpp.

References emergencyStop(), and init().

◆ ~vpRobotFlirPtu()

vpRobotFlirPtu::~vpRobotFlirPtu ( )
virtual

Destructor.

Definition at line 130 of file vpRobotFlirPtu.cpp.

References disconnect(), and stopMotion().

Member Function Documentation

◆ connect()

void vpRobotFlirPtu::connect ( const std::string &  portname,
int  baudrate = 9600 
)

Connect to FLIR PTU.

Parameters
[in]portname: Connect to serial/socket.
[in]baudrate: Use baud rate (default: 9600).
See also
disconnect()
Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 531 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, getLimits(), m_cer, m_connected, and m_status.

◆ disconnect()

◆ emergencyStop()

void vpRobotFlirPtu::emergencyStop ( int  signo)
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().

◆ get_cVe()

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

Returns
Velocity twist transformation.
See also
set_eMc(), get_eMc()
Examples:
servoFlirPtuIBVS.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 239 of file vpRobotFlirPtu.cpp.

References vpVelocityTwistMatrix::buildFrom(), vpHomogeneousMatrix::inverse(), and m_eMc.

◆ get_eJe() [1/2]

void vpRobotFlirPtu::get_eJe ( vpMatrix eJe)
virtual

Get the robot Jacobian expressed in the end-effector frame.

Parameters
[out]eJe: End-effector frame Jacobian.
See also
get_fJe()

Implements vpRobot.

Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 168 of file vpRobotFlirPtu.cpp.

References get_eJe().

◆ get_eJe() [2/2]

vpMatrix vpRobotFlirPtu::get_eJe ( )

Get the robot Jacobian expressed in the end-effector frame.

Returns
End-effector frame Jacobian.
See also
get_fJe()

Definition at line 149 of file vpRobotFlirPtu.cpp.

References vpRobot::eJe, getPosition(), vpRobot::JOINT_STATE, and vpArray2D< Type >::resize().

Referenced by get_eJe().

◆ get_eMc()

vpHomogeneousMatrix vpRobotFlirPtu::get_eMc ( ) const
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().

◆ get_fJe() [1/2]

void vpRobotFlirPtu::get_fJe ( vpMatrix fJe)
virtual

Get the robot Jacobian expressed in the robot reference frame.

Parameters
[out]fJe: Base (or reference) frame Jacobian.
See also
get_fJe()

Implements vpRobot.

Definition at line 196 of file vpRobotFlirPtu.cpp.

References get_fJe().

◆ get_fJe() [2/2]

vpMatrix vpRobotFlirPtu::get_fJe ( )

Get the robot Jacobian expressed in the robot reference frame.

Returns
Base (or reference) frame Jacobian.
See also
get_eJe()

Definition at line 176 of file vpRobotFlirPtu.cpp.

References vpRobot::fJe, getPosition(), vpRobot::JOINT_STATE, and vpArray2D< Type >::resize().

Referenced by get_fJe().

◆ get_fMe()

vpMatrix vpRobotFlirPtu::get_fMe ( )

Get the robot geometric model corresponding to the homogeneous transformation between base (or reference) frame and end-effector frame.

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

◆ getDisplacement()

void vpRobotFlirPtu::getDisplacement ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
virtual

Get a displacement.

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

◆ getJointPosition()

void vpRobotFlirPtu::getJointPosition ( vpColVector q)
protected

Get robot joint positions.

Parameters
[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().

◆ getLimits()

void vpRobotFlirPtu::getLimits ( )
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().

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

◆ getNetworkGateway()

std::string vpRobotFlirPtu::getNetworkGateway ( )

When connected to the PTU by serial, get the PTU network gateway.

See also
getNetworkIP()
Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 886 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_cer, m_connected, and m_status.

◆ getNetworkHostName()

std::string vpRobotFlirPtu::getNetworkHostName ( )

When connected to the PTU, get the PTU network hostname.

See also
getNetworkIP()
Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

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

◆ getNetworkIP()

std::string vpRobotFlirPtu::getNetworkIP ( )

When connected to the PTU by serial, get the PTU network IP address.

See also
getNetworkGateway()
Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 866 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_cer, m_connected, and m_status.

◆ getPanPosLimits()

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.

See also
getTiltPosLimits(), getPanTiltVelMax(), setPanPosLimits()
Examples:
testRobotFlirPtu.cpp.

Definition at line 650 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_connected, m_pos_max_tics, and m_pos_min_tics.

◆ getPanTiltVelMax()

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.

See also
getPanPosLimits(), getTiltPosLimits()
Examples:
testRobotFlirPtu.cpp.

Definition at line 688 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_connected, and m_vel_max_tics.

◆ getPosition() [1/2]

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

Get robot position.

Parameters
[in]frame: Considered cartesian frame or joint state.
[out]q: Position of the arm.

Implements vpRobot.

Examples:
testRobotFlirPtu.cpp.

Definition at line 441 of file vpRobotFlirPtu.cpp.

References getJointPosition(), and vpRobot::JOINT_STATE.

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

◆ getPosition() [2/2]

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

Return the current robot position in the specified frame.

Definition at line 216 of file vpRobot.cpp.

References vpRobot::getPosition().

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

◆ getRobotState()

virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtualinherited

◆ getTiltPosLimits()

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.

See also
getPanPosLimits(), getPanTiltVelMax(), setTiltPosLimits()
Examples:
testRobotFlirPtu.cpp.

Definition at line 669 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_connected, m_pos_max_tics, and m_pos_min_tics.

◆ init()

void vpRobotFlirPtu::init ( void  )
protectedvirtual

◆ reset()

void vpRobotFlirPtu::reset ( )

Reset PTU axis.

Examples:
testRobotFlirPtu.cpp.

Definition at line 832 of file vpRobotFlirPtu.cpp.

References vpException::fatalError, m_cer, m_connected, and m_status.

◆ 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>
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;
}

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

◆ set_eMc()

void vpRobotFlirPtu::set_eMc ( vpHomogeneousMatrix eMc)
inline

Set constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.

Examples:
servoFlirPtuIBVS.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 135 of file vpRobotFlirPtu.h.

References vpRobot::init(), vpRobot::setPosition(), vpRobot::setRobotState(), and vpRobot::setVelocity().

◆ setCartVelocity()

void vpRobotFlirPtu::setCartVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector v 
)
protected

Send to the controller a 6-dim velocity skew vector expressed in a Cartesian frame.

Parameters
[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().

◆ setJointVelocity()

void vpRobotFlirPtu::setJointVelocity ( const vpColVector qdot)
protected

Send a joint velocity to the controller.

Parameters
[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().

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)
inherited

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

References vpRobot::maxTranslationVelocity.

Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().

◆ setPanPosLimits()

void vpRobotFlirPtu::setPanPosLimits ( const vpColVector pan_limits)

Modify pan position limit.

Parameters
pan_limits: 2-dim vector that contains pan min and max limits in rad.
See also
getPanPosLimits()
Examples:
testRobotFlirPtu.cpp.

Definition at line 707 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and vpArray2D< Type >::size().

◆ setPosition()

void vpRobotFlirPtu::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector q 
)
virtual

Set a position to reach.

Parameters
[in]frame: Considered cartesian frame or joint state.
[in]q: Position to reach.

Implements vpRobot.

Examples:
testRobotFlirPtu.cpp.

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

◆ setPositioningVelocity()

void vpRobotFlirPtu::setPositioningVelocity ( double  velocity)

Set the velocity used for a position control.

Parameters
velocity: Velocity in % of the maximum velocity between [0, 100]. Default value is 20.
Examples:
testRobotFlirPtu.cpp.

Definition at line 767 of file vpRobotFlirPtu.cpp.

References m_positioning_velocity.

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotFlirPtu::setRobotState ( vpRobot::vpRobotStateType  newState)
virtual

Change the robot state.

Parameters
newState: New requested robot state if the robot is connected. If the robot is not connected, we return the current state.

Reimplemented from vpRobot.

Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

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

◆ setTiltPosLimits()

void vpRobotFlirPtu::setTiltPosLimits ( const vpColVector tilt_limits)

Modify tilt position limit.

Parameters
tilt_limits: 2-dim vector that contains tilt min and max limits in rad.
See also
getPanPosLimits()
Examples:
testRobotFlirPtu.cpp.

Definition at line 737 of file vpRobotFlirPtu.cpp.

References disconnect(), vpException::fatalError, m_cer, m_connected, m_status, and vpArray2D< Type >::size().

◆ setVelocity()

void vpRobotFlirPtu::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector vel 
)
virtual

Send to the controller a velocity in a given frame.

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

Examples:
servoFlirPtuIBVS.cpp, testRobotFlirPtu.cpp, and tutorial-flir-ptu-ibvs.cpp.

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.

◆ setVerbose()

◆ stopMotion()

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

Member Data Documentation

◆ areJointLimitsAvailable

◆ eJe

vpMatrix vpRobot::eJe
protectedinherited

◆ eJeAvailable

int vpRobot::eJeAvailable
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().

◆ fJe

vpMatrix vpRobot::fJe
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=().

◆ fJeAvailable

int vpRobot::fJeAvailable
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().

◆ m_cer

◆ m_connected

◆ m_eMc

vpHomogeneousMatrix vpRobotFlirPtu::m_eMc
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().

◆ m_njoints

int vpRobotFlirPtu::m_njoints
protected

Definition at line 169 of file vpRobotFlirPtu.h.

Referenced by setPosition().

◆ m_pos_max_tics

std::vector<int> vpRobotFlirPtu::m_pos_max_tics
protected

Pan min/max position in robot tics unit.

Definition at line 164 of file vpRobotFlirPtu.h.

Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), and setPosition().

◆ m_pos_min_tics

std::vector<int> vpRobotFlirPtu::m_pos_min_tics
protected

Tilt min/max position in robot tics unit.

Definition at line 165 of file vpRobotFlirPtu.h.

Referenced by getLimits(), getPanPosLimits(), getTiltPosLimits(), and setPosition().

◆ m_positioning_velocity

double vpRobotFlirPtu::m_positioning_velocity
protected

Definition at line 170 of file vpRobotFlirPtu.h.

Referenced by setPosition(), and setPositioningVelocity().

◆ m_res

std::vector<double> vpRobotFlirPtu::m_res
protected

Pan/tilt tic resolution in deg.

Definition at line 167 of file vpRobotFlirPtu.h.

Referenced by getLimits(), and getNetworkHostName().

◆ m_status

◆ m_vel_max_tics

std::vector<int> vpRobotFlirPtu::m_vel_max_tics
protected

Pan/tilt max velocity in robot tics unit.

Definition at line 166 of file vpRobotFlirPtu.h.

Referenced by getLimits(), getPanTiltVelMax(), setJointVelocity(), and setPosition().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

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

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 97 of file vpRobot.h.

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

◆ nDof

◆ qmax

◆ qmin

◆ verbose_