Visual Servoing Platform  version 3.6.1 under development (2024-04-27)
vpReflexTakktile2.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 the Reflex Takktile 2 hand from Right Hand Robotics.
33  *
34 *****************************************************************************/
35 
36 #ifndef _vpReflexTakktile2_h_
37 #define _vpReflexTakktile2_h_
38 
39 #include <visp3/core/vpConfig.h>
40 #ifdef VISP_HAVE_TAKKTILE2
41 
42 #include <string>
43 #include <vector>
44 
45 #include <visp3/core/vpColVector.h>
46 
66 class VISP_EXPORT vpReflexTakktile2
67 {
68 public:
69  class HandInfo
70  {
71  public:
72  std::vector<float> proximal;
73  std::vector<float> distal_approx;
74  std::vector<std::vector<int> > pressure;
75  std::vector<std::vector<bool> > contact;
76 
77  std::vector<float> joint_angle;
78  std::vector<float> raw_angle;
79  std::vector<float> velocity;
80  std::vector<float> load;
81  std::vector<float> voltage;
82 
83  std::vector<uint32_t> temperature;
84  std::vector<std::string> error_state;
85 
86  HandInfo();
87  ~HandInfo() {}
88 
89  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const HandInfo &hand);
90  };
91 
93  virtual ~vpReflexTakktile2();
94 
95  void calibrate();
96 
97  void disableTorque();
98 
99  HandInfo getHandInfo();
100 
101  int getNumFingers() const;
102  int getNumSensorsPerFinger() const;
103  int getNumServos() const;
104 
105  vpColVector getPosition() const;
106  vpColVector getVelocity() const;
107 
108  void open();
109 
114  void setFingerConfigFile(const std::string &finger_file_name) { m_finger_file_name = finger_file_name; }
115 
120  void setMotorConfigFile(const std::string &motor_file_name) { m_motor_file_name = motor_file_name; }
121 
127  void setNetworkInterface(const std::string &network_interface = "eth0") { m_network_interface = network_interface; }
128 
129  void setPosition(const vpColVector &targets);
130 
135  void setTactileConfigFile(const std::string &tactile_file_name) { m_tactile_file_name = tactile_file_name; }
136 
137  void setTactileThreshold(int threshold);
138  void setTactileThreshold(const std::vector<int> &thresholds);
139 
140  void setPositioningVelocity(const vpColVector &targets);
141  void setVelocityUntilAnyContact(const vpColVector &targets);
142  void setVelocityUntilEachContact(const vpColVector &targets);
143 
144  void wait(int milliseconds);
145 
146 protected:
147  std::string m_network_interface;
148  std::string m_finger_file_name;
149  std::string m_tactile_file_name;
150  std::string m_motor_file_name;
152 
153 private:
154  // Implementation
155  class Impl;
156  Impl *m_impl;
157 };
158 
159 #endif
160 #endif
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
std::vector< uint32_t > temperature
std::vector< float > joint_angle
std::vector< std::vector< bool > > contact
std::vector< std::vector< int > > pressure
std::vector< std::string > error_state
std::vector< float > load
std::vector< float > raw_angle
std::vector< float > proximal
std::vector< float > voltage
std::vector< float > distal_approx
std::vector< float > velocity
std::string m_finger_file_name
std::string m_tactile_file_name
std::string m_network_interface
void setMotorConfigFile(const std::string &motor_file_name)
void setTactileConfigFile(const std::string &tactile_file_name)
void setNetworkInterface(const std::string &network_interface="eth0")
std::string m_motor_file_name
void setFingerConfigFile(const std::string &finger_file_name)