Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotFlirPtu.h
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Interface for Flir Ptu Cpi robot.
32 */
33
38
39#ifndef vpRobotFlirPtu_h
40#define vpRobotFlirPtu_h
41
42#include <visp3/core/vpConfig.h>
43
44#ifdef VISP_HAVE_FLIR_PTU_SDK
45
46#include <visp3/core/vpHomogeneousMatrix.h>
47#include <visp3/robot/vpRobot.h>
48#include <visp3/robot/vpRobotException.h>
49
96class VISP_EXPORT vpRobotFlirPtu : public vpRobot
97{
98public:
100 virtual ~vpRobotFlirPtu();
101
102 void connect(const std::string &portname, int baudrate = 9600);
103 void disconnect();
104
105 void get_eJe(vpMatrix &eJe) VP_OVERRIDE;
107 void get_fJe(vpMatrix &fJe) VP_OVERRIDE;
110
116 vpVelocityTwistMatrix get_cVe() const;
117
118 void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE;
119
120 std::string getNetworkIP();
121 std::string getNetworkGateway();
122 std::string getNetworkHostName();
123
124 void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE;
125 vpColVector getPanPosLimits();
126 vpColVector getTiltPosLimits();
127 vpColVector getPanTiltVelMax();
128
129 void reset();
130
135 void set_eMc(vpHomogeneousMatrix &eMc) { m_eMc = eMc; }
136 void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE;
137 void setPanPosLimits(const vpColVector &pan_limits);
138 void setTiltPosLimits(const vpColVector &tilt_limits);
139
140 void setPositioningVelocity(double velocity);
142 void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE;
143 void stopMotion();
144
145 static void emergencyStop(int signo);
146
147protected:
148 void init();
149 void getLimits();
150 void getJointPosition(vpColVector &q);
151 void setCartVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &v);
152 void setJointVelocity(const vpColVector &qdot);
153
154private:
155 double tics2deg(int axis, int tics);
156 double tics2rad(int axis, int tics);
157 int rad2tics(int axis, double rad);
158
159protected:
161
162 struct cerial *m_cer;
163 uint16_t m_status;
164 std::vector<int> m_pos_max_tics;
165 std::vector<int> m_pos_min_tics;
166 std::vector<int> m_vel_max_tics;
167 std::vector<double> m_res;
171};
172END_VISP_NAMESPACE
173#endif
174#endif
Implementation of column vector and the associated operations.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
vpHomogeneousMatrix m_eMc
Constant transformation between end-effector and tool (or camera) frame.
std::vector< int > m_pos_max_tics
Pan min/max position in robot tics unit.
void connect(const std::string &portname, int baudrate=9600)
double m_positioning_velocity
std::vector< double > m_res
Pan/tilt tic resolution in deg.
void set_eMc(vpHomogeneousMatrix &eMc)
std::vector< int > m_vel_max_tics
Pan/tilt max velocity in robot tics unit.
struct cerial * m_cer
vpHomogeneousMatrix get_eMc() const
std::vector< int > m_pos_min_tics
Tilt min/max position in robot tics unit.
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition vpRobot.h:103
vpControlFrameType
Definition vpRobot.h:74
virtual void get_eJe(vpMatrix &_eJe)=0
Get the robot Jacobian expressed in the end-effector frame.
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)=0
Get the robot position (frame has to be specified).
vpRobotStateType
Definition vpRobot.h:62
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition vpRobot.h:107
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:200
virtual void init()=0
virtual void get_fJe(vpMatrix &_fJe)=0
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
vpRobot(void)
Definition vpRobot.cpp:49
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.