mia_hand_description  rel 1.0.0
mia_thumb_opp_passivejoints.h
Go to the documentation of this file.
1 /*********************************************************************************************************
2  thumb_opp_passive_joints class.
3  Author: Prensilia srl
4  version: 1.0
5 **********************************************************************************************************/
6 #ifndef MIA_THUMB_OPP_PASSIVEJOINTS_H
7 #define MIA_THUMB_OPP_PASSIVEJOINTS_H
8 
9 #include "ros/ros.h"
10 #include "std_msgs/String.h"
11 #include "sensor_msgs/JointState.h"
12 #include <iostream>
13 #include <string>
14 #include <cmath>
15 #include <urdf/model.h>
16 #include <joint_limits_interface/joint_limits.h>
17 #include <joint_limits_interface/joint_limits_interface.h>
18 #include <joint_limits_interface/joint_limits_rosparam.h>
19 #include <joint_limits_interface/joint_limits_urdf.h>
20 
24 namespace mia_hand
25 {
26 
33 {
34 public:
35 
39  thumb_opp_passive_joint(); // Constructor, parameters with default values.
40 
45 
46 
51  void init(const bool LoadURDFInfo_ = false);
52 
59  double GetThumbOppPosition(double j_index_flex_pos);
60 
71  bool LoadURDFInfo();
72 
73 
78  std::string j_index_name ;
79 
84  std::string j_thumb_name ;
85 
90  std::string robot_description_ ;
91 
96  double ThMinPos;
97 
102  double ThMaxPos;
103 
104 private:
109  ros::NodeHandle n;
110 
118  std::string getURDF(std::string param_name) const;
119 
120 
121 };
122 } // namespace
123 
124 #endif // MIA_THUMB_OPP_PASSIVEJOINTS_H
mia_hand::thumb_opp_passive_joint::~thumb_opp_passive_joint
~thumb_opp_passive_joint()
Class destructor.
Definition: mia_thumb_opp_passivejoints.cpp:35
mia_hand::thumb_opp_passive_joint::getURDF
std::string getURDF(std::string param_name) const
Get the name of the URDF.
Definition: mia_thumb_opp_passivejoints.cpp:98
mia_hand::thumb_opp_passive_joint::GetThumbOppPosition
double GetThumbOppPosition(double j_index_flex_pos)
Evaluate the position of the thumb opposition based on index flexion state.
Definition: mia_thumb_opp_passivejoints.cpp:38
mia_hand::thumb_opp_passive_joint::LoadURDFInfo
bool LoadURDFInfo()
Load Info from loaded URDF.
Definition: mia_thumb_opp_passivejoints.cpp:60
mia_hand::thumb_opp_passive_joint::ThMinPos
double ThMinPos
Lower Limit of the thumb_opp joint.
Definition: mia_thumb_opp_passivejoints.h:104
mia_hand::thumb_opp_passive_joint::j_thumb_name
std::string j_thumb_name
Name of the thumb_opp joint specified in the URDF.
Definition: mia_thumb_opp_passivejoints.h:92
mia_hand::thumb_opp_passive_joint
thumb_opp_passive_joints class.
Definition: mia_thumb_opp_passivejoints.h:36
mia_hand::thumb_opp_passive_joint::init
void init(const bool LoadURDFInfo_=false)
Initialize class.
Definition: mia_thumb_opp_passivejoints.cpp:19
mia_hand
namespace containing thumb_opp_passive_joints class.
Definition: mia_thumb_opp_passivejoints.h:24
mia_hand::thumb_opp_passive_joint::thumb_opp_passive_joint
thumb_opp_passive_joint()
Class constructor.
Definition: mia_thumb_opp_passivejoints.cpp:14
mia_hand::thumb_opp_passive_joint::ThMaxPos
double ThMaxPos
Upper Limit of the thumb_opp joint.
Definition: mia_thumb_opp_passivejoints.h:110
mia_hand::thumb_opp_passive_joint::n
ros::NodeHandle n
A ROS node variable.
Definition: mia_thumb_opp_passivejoints.h:117
mia_hand::thumb_opp_passive_joint::robot_description_
std::string robot_description_
Name of parameter describing the robot description loaded in the ROS parameter server.
Definition: mia_thumb_opp_passivejoints.h:98
mia_hand::thumb_opp_passive_joint::j_index_name
std::string j_index_name
Name of the index_fle joint specified in the URDF.
Definition: mia_thumb_opp_passivejoints.h:86