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