mia_hand_driver
rel 1.0.0
|
Go to the documentation of this file.
10 #ifndef MIA_HAND_CPP_DRIVER_H
11 #define MIA_HAND_CPP_DRIVER_H
104 void getFingerSgRaw(uint8_t fin_id, int16_t& nor_for, int16_t& tan_for);
126 void closeGrasp(
char grasp_id, int16_t close_percent);
135 void setThuGraspRef(
char grasp_id, int16_t rest, int16_t pos, int16_t delay);
144 void setIndGraspRef(
char grasp_id, int16_t rest, int16_t pos, int16_t delay);
153 void setMrlGraspRef(
char grasp_id, int16_t rest, int16_t pos, int16_t delay);
189 std::string
numToStr(int16_t num, int8_t n_digits);
236 #endif // MIA_HAND_CPP_DRIVER_H
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.
bool is_connected_
True if the Mia hand is conncted, False otherwise.
bool connection_trd_on_
True if check_connection_trd_ thread is running.
void switchSpeStream(bool b_on_off)
Manage the streaming of the motors velocity data.
CppDriver()
Class constructor.
std::string numToStr(int16_t num, int8_t n_digits)
Convert integer number into string.
void pollSerialPort()
Function of the serial_poll_trd_ thread.
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...
void setThuGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for thumb flexion motor.
SerialPort serial_port_
Hanlder of the serial port_num.
Struct containing all info that could regard a Mia hand motor.
void setMotorSpe(uint8_t fin_id, int16_t mot_spe)
Set the target velocity of a specific motor of the Mia hand.
std::mutex connection_mtx_
int16_t getMotorPos(uint8_t fin_id)
Get the current position of a specific motor of the Mia hand.
bool disconnect()
Disconnect the Mia hand closing the serial port.
std::thread check_connection_trd_
Thread to execute the check of the Mia hand connection.
std::mutex finger_data_mtx_
Mutex to handle the reading of the motors finger data.
void switchAnaStream(bool b_on_off)
Manage the streaming of analog input data (as the straing gauge force sensors).
Class to handle a serial port and its serial communication protocol.
int16_t getMotorSpe(uint8_t fin_id)
Get the current velocity of a specific motor of the Mia hand.
std::thread serial_poll_trd_
Thread to execute the parse of the data received by the Mia hand.
void switchPosStream(bool b_on_off)
Manage the streaming of the motors position data.
bool isConnected()
Function returning the connection status of the Mia hand.
void setMrlGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for MRL flexion motor.
FingerSerialInfo mrl_info_
Info about the mrl flexion motor.
int16_t getMotorCur(uint8_t fin_id)
Get the current currently absorbed by a specific motor of the Mia hand.
FingerSerialInfo index_info_
Info about the index flexion motor.
void checkConnection()
Function of the check_connection_trd_ thread.
bool connectToPort(uint16_t port_num)
Open serial port used to plug Mia hand.
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...
void setMotorPos(uint8_t fin_id, int16_t mot_pos)
Set the target position of a specific motor of the Mia hand.
void setIndGraspRef(char grasp_id, int16_t rest, int16_t pos, int16_t delay)
Set grasp parameter for Index flexion + thumb abduction motor.
void switchCurStream(bool b_on_off)
Manage the streaming of the current absorbed by Mi hand motors.
~CppDriver()
Class destructor.
void setFingerFor(uint8_t fin_id, int16_t fin_for)
Set the target force of a specific motor of the Mia hand.
FingerSerialInfo thumb_info_
Info about the thumb flexion motor.
bool serial_trd_on_
True if serial_poll_trd_ thread is running.