Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpRobotFlirPtu.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #ifndef vpRobotFlirPtu_h
40 #define vpRobotFlirPtu_h
41 
47 #include <visp3/core/vpConfig.h>
48 
49 #ifdef VISP_HAVE_FLIR_PTU_SDK
50 
51 #include <visp3/core/vpHomogeneousMatrix.h>
52 #include <visp3/robot/vpRobot.h>
53 #include <visp3/robot/vpRobotException.h>
54 
96 class VISP_EXPORT vpRobotFlirPtu : public vpRobot
97 {
98 public:
100  virtual ~vpRobotFlirPtu();
101 
102  void connect(const std::string &portname, int baudrate = 9600);
103  void disconnect();
104 
105  void get_eJe(vpMatrix &eJe);
106  vpMatrix get_eJe();
107  void get_fJe(vpMatrix &fJe);
108  vpMatrix get_fJe();
109  vpMatrix get_fMe();
110 
115  vpHomogeneousMatrix get_eMc() const { return m_eMc; }
116  vpVelocityTwistMatrix get_cVe() const;
117 
119 
120  std::string getNetworkIP();
121  std::string getNetworkGateway();
122  std::string getNetworkHostName();
123 
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);
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);
143  void stopMotion();
144 
145  static void emergencyStop(int signo);
146 
147 protected:
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 
154 private:
155  double tics2deg(int axis, int tics);
156  double tics2rad(int axis, int tics);
157  int rad2tics(int axis, double rad);
158 
159 protected:
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 };
172 
173 #endif
174 #endif
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:164
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
vpHomogeneousMatrix m_eMc
Constant transformation between end-effector and tool (or camera) frame.
struct cerial * m_cer
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::vector< double > m_res
Pan/tilt tic resolution in deg.
std::vector< int > m_vel_max_tics
Pan/tilt max velocity in robot tics unit.
virtual void get_eJe(vpMatrix &_eJe)=0
Get the robot Jacobian expressed in the end-effector frame.
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
vpControlFrameType
Definition: vpRobot.h:75
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
vpRobotStateType
Definition: vpRobot.h:64
void set_eMc(vpHomogeneousMatrix &eMc)
std::vector< int > m_pos_max_tics
Pan min/max position in robot tics unit.
virtual void init()=0
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Get the robot position (frame has to be specified).
virtual void get_fJe(vpMatrix &_fJe)=0
double m_positioning_velocity
std::vector< int > m_pos_min_tics
Tilt min/max position in robot tics unit.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
vpHomogeneousMatrix get_eMc() const
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0