mia_hand_driver  rel 1.0.0
cpp_driver.h
Go to the documentation of this file.
1 /*********************************************************************************************************
2 Modifyed by Author: Prensilia srl
3 Desc: Cpp driver class of the Mia hand
4 
5 version 1.0
6 
7 **********************************************************************************************************/
8 
9 
10 #ifndef MIA_HAND_CPP_DRIVER_H
11 #define MIA_HAND_CPP_DRIVER_H
12 
14 #include <thread>
15 
16 namespace mia_hand
17 {
18 class CppDriver
19 {
20 public:
21 
25  CppDriver();
26 
30  ~CppDriver();
31 
37  bool connectToPort(uint16_t port_num);
38 
43  bool disconnect();
44 
49  bool isConnected();
50 
57  void setMotorPos(uint8_t fin_id, int16_t mot_pos);
58 
65  void setMotorSpe(uint8_t fin_id, int16_t mot_spe);
66 
73  void setFingerFor(uint8_t fin_id, int16_t fin_for);
74 
80  int16_t getMotorPos(uint8_t fin_id);
81 
87  int16_t getMotorSpe(uint8_t fin_id);
88 
94  int16_t getMotorCur(uint8_t fin_id);
95 
104  void getFingerSgRaw(uint8_t fin_id, int16_t& nor_for, int16_t& tan_for);
105 
111  void openGrasp(char grasp_id);
112 
118  void closeGrasp(char grasp_id);
119 
126  void closeGrasp(char grasp_id, int16_t close_percent);
127 
135  void setThuGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay);
136 
144  void setIndGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay);
145 
153  void setMrlGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay);
154 
159  void switchPosStream(bool b_on_off);
160 
165  void switchSpeStream(bool b_on_off);
166 
171  void switchAnaStream(bool b_on_off);
172 
177  void switchCurStream(bool b_on_off);
178 
179 private:
180 
182 
189  std::string numToStr(int16_t num, int8_t n_digits);
190 
197  void pollSerialPort();
198 
204  void checkConnection();
205 
210  std::thread serial_poll_trd_;
211 
212  bool serial_trd_on_;
213  std::mutex finger_data_mtx_;
214 
215 
220  std::thread check_connection_trd_;
221 
223  bool is_checking_on_;
224 
225  std::mutex reply_mtx_;
226  std::mutex connection_mtx_;
227 
231 
233 };
234 } // namespace
235 
236 #endif // MIA_HAND_CPP_DRIVER_H
mia_hand::CppDriver::getFingerSgRaw
void getFingerSgRaw(uint8_t fin_id, int16_t &nor_for, int16_t &tan_for)
Get the current output of the force sensor of a specific finger of the Mia hand.
Definition: cpp_driver.cpp:238
mia_hand::CppDriver::is_connected_
bool is_connected_
True if the Mia hand is conncted, False otherwise.
Definition: cpp_driver.h:244
mia_hand::CppDriver::connection_trd_on_
bool connection_trd_on_
True if check_connection_trd_ thread is running.
Definition: cpp_driver.h:234
mia_hand::CppDriver::switchSpeStream
void switchSpeStream(bool b_on_off)
Manage the streaming of the motors velocity data.
Definition: cpp_driver.cpp:423
mia_hand::CppDriver::CppDriver
CppDriver()
Class constructor.
Definition: cpp_driver.cpp:5
mia_hand::CppDriver::numToStr
std::string numToStr(int16_t num, int8_t n_digits)
Convert integer number into string.
Definition: cpp_driver.cpp:453
mia_hand::CppDriver::pollSerialPort
void pollSerialPort()
Function of the serial_poll_trd_ thread.
Definition: cpp_driver.cpp:468
mia_hand::CppDriver::openGrasp
void openGrasp(char grasp_id)
Go to rest pose of a grasp type Move all the Mia hand fingers to the rest pose of a specific grasp ty...
Definition: cpp_driver.cpp:276
mia_hand::CppDriver::reply_mtx_
std::mutex reply_mtx_
Definition: cpp_driver.h:237
mia_hand::CppDriver::setThuGraspRef
void setThuGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for thumb flexion motor.
Definition: cpp_driver.cpp:314
serial_port.h
mia_hand::CppDriver::serial_port_
SerialPort serial_port_
Hanlder of the serial port_num.
Definition: cpp_driver.h:193
mia_hand::FingerSerialInfo
Struct containing all info that could regard a Mia hand motor.
Definition: serial_port.h:28
mia_hand::CppDriver::setMotorSpe
void setMotorSpe(uint8_t fin_id, int16_t mot_spe)
Set the target velocity of a specific motor of the Mia hand.
Definition: cpp_driver.cpp:84
mia_hand::CppDriver::connection_mtx_
std::mutex connection_mtx_
Definition: cpp_driver.h:238
mia_hand::CppDriver::is_checking_on_
bool is_checking_on_
Definition: cpp_driver.h:235
mia_hand::CppDriver::getMotorPos
int16_t getMotorPos(uint8_t fin_id)
Get the current position of a specific motor of the Mia hand.
Definition: cpp_driver.cpp:130
mia_hand::CppDriver::disconnect
bool disconnect()
Disconnect the Mia hand closing the serial port.
Definition: cpp_driver.cpp:37
mia_hand::CppDriver::check_connection_trd_
std::thread check_connection_trd_
Thread to execute the check of the Mia hand connection.
Definition: cpp_driver.h:232
mia_hand::CppDriver::finger_data_mtx_
std::mutex finger_data_mtx_
Mutex to handle the reading of the motors finger data.
Definition: cpp_driver.h:225
mia_hand::CppDriver::switchAnaStream
void switchAnaStream(bool b_on_off)
Manage the streaming of analog input data (as the straing gauge force sensors).
Definition: cpp_driver.cpp:433
mia_hand::SerialPort
Class to handle a serial port and its serial communication protocol.
Definition: serial_port.h:42
mia_hand::CppDriver::getMotorSpe
int16_t getMotorSpe(uint8_t fin_id)
Get the current velocity of a specific motor of the Mia hand.
Definition: cpp_driver.cpp:166
mia_hand::CppDriver::serial_poll_trd_
std::thread serial_poll_trd_
Thread to execute the parse of the data received by the Mia hand.
Definition: cpp_driver.h:222
mia_hand
Definition: cpp_driver.h:16
mia_hand::CppDriver
Definition: cpp_driver.h:24
mia_hand::CppDriver::switchPosStream
void switchPosStream(bool b_on_off)
Manage the streaming of the motors position data.
Definition: cpp_driver.cpp:413
mia_hand::CppDriver::isConnected
bool isConnected()
Function returning the connection status of the Mia hand.
Definition: cpp_driver.cpp:51
mia_hand::CppDriver::setMrlGraspRef
void setMrlGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for MRL flexion motor.
Definition: cpp_driver.cpp:380
mia_hand::CppDriver::mrl_info_
FingerSerialInfo mrl_info_
Info about the mrl flexion motor.
Definition: cpp_driver.h:242
mia_hand::CppDriver::getMotorCur
int16_t getMotorCur(uint8_t fin_id)
Get the current currently absorbed by a specific motor of the Mia hand.
Definition: cpp_driver.cpp:202
mia_hand::CppDriver::index_info_
FingerSerialInfo index_info_
Info about the index flexion motor.
Definition: cpp_driver.h:241
mia_hand::CppDriver::checkConnection
void checkConnection()
Function of the check_connection_trd_ thread.
Definition: cpp_driver.cpp:479
mia_hand::CppDriver::connectToPort
bool connectToPort(uint16_t port_num)
Open serial port used to plug Mia hand.
Definition: cpp_driver.cpp:30
mia_hand::CppDriver::closeGrasp
void closeGrasp(char grasp_id)
Go to closed pose of a grasp type Move all the Mia hand fingers to the closed pose of a specific gras...
Definition: cpp_driver.cpp:284
mia_hand::CppDriver::setMotorPos
void setMotorPos(uint8_t fin_id, int16_t mot_pos)
Set the target position of a specific motor of the Mia hand.
Definition: cpp_driver.cpp:60
mia_hand::CppDriver::setIndGraspRef
void setIndGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for Index flexion + thumb abduction motor.
Definition: cpp_driver.cpp:347
mia_hand::CppDriver::switchCurStream
void switchCurStream(bool b_on_off)
Manage the streaming of the current absorbed by Mi hand motors.
Definition: cpp_driver.cpp:443
mia_hand::CppDriver::~CppDriver
~CppDriver()
Class destructor.
Definition: cpp_driver.cpp:22
mia_hand::CppDriver::setFingerFor
void setFingerFor(uint8_t fin_id, int16_t fin_for)
Set the target force of a specific motor of the Mia hand.
Definition: cpp_driver.cpp:108
mia_hand::CppDriver::thumb_info_
FingerSerialInfo thumb_info_
Info about the thumb flexion motor.
Definition: cpp_driver.h:240
mia_hand::CppDriver::serial_trd_on_
bool serial_trd_on_
True if serial_poll_trd_ thread is running.
Definition: cpp_driver.h:224