humotion / examples / meka / include / mekajointinterface.h @ ddccf279
History | View | Annotate | Download (2.87 KB)
1 |
#pragma once
|
---|---|
2 |
#include <humotion/server/joint_interface.h> |
3 |
#include <humotion/server/server.h> |
4 |
#include <boost/bimap.hpp> |
5 |
//#include "meka_data_receiver.h"
|
6 |
//class MekaDataReceiver;
|
7 |
#include "ros/ros.h" |
8 |
#include "sensor_msgs/JointState.h" |
9 |
#include "trajectory_msgs/JointTrajectory.h" |
10 |
|
11 |
class MekaJointInterface : public humotion::server::JointInterface{ |
12 |
public:
|
13 |
MekaJointInterface(std::string _input_scope, std::string _output_scope); |
14 |
~MekaJointInterface(); |
15 |
|
16 |
//void fetch_position(Device *dev, double timestamp);
|
17 |
//void fetch_speed(Device *dev, double timestamp);
|
18 |
//void fetch_position(int id, double value, double timestamp);
|
19 |
//void fetch_speed(int id, double value, double timestamp);
|
20 |
void run();
|
21 |
|
22 |
enum JOINT_ID_ENUM{
|
23 |
ICUB_ID_NECK_TILT = 0,
|
24 |
ICUB_ID_NECK_ROLL = 1,
|
25 |
ICUB_ID_NECK_PAN = 2,
|
26 |
ICUB_ID_EYES_BOTH_UD = 3,
|
27 |
ICUB_ID_EYES_PAN = 4,
|
28 |
ICUB_ID_EYES_VERGENCE = 5,
|
29 |
//the following ids are used for remapping:
|
30 |
ICUB_ID_EYES_LEFT_LR, |
31 |
ICUB_ID_EYES_RIGHT_LR, |
32 |
ICUB_ID_EYES_LEFT_LID_LOWER, |
33 |
ICUB_ID_EYES_LEFT_LID_UPPER, |
34 |
ICUB_ID_EYES_RIGHT_LID_LOWER, |
35 |
ICUB_ID_EYES_RIGHT_LID_UPPER, |
36 |
ICUB_ID_EYES_LEFT_BROW, |
37 |
ICUB_ID_EYES_RIGHT_BROW, |
38 |
ICUB_ID_LIP_LEFT_UPPER, |
39 |
ICUB_ID_LIP_LEFT_LOWER, |
40 |
ICUB_ID_LIP_CENTER_UPPER, |
41 |
ICUB_ID_LIP_CENTER_LOWER, |
42 |
ICUB_ID_LIP_RIGHT_UPPER, |
43 |
ICUB_ID_LIP_RIGHT_LOWER, |
44 |
ICUB_JOINT_ID_ENUM_SIZE |
45 |
}; |
46 |
|
47 |
static const int MAIN_LOOP_FREQUENCY = 50; |
48 |
|
49 |
protected:
|
50 |
void disable_joint(int e); |
51 |
void publish_target_position(int e); |
52 |
void enable_joint(int e); |
53 |
void execute_motion();
|
54 |
|
55 |
private:
|
56 |
void incoming_jointstates(const sensor_msgs::JointState & msg); |
57 |
void store_dummy_data(int id, double timestamp); |
58 |
void store_min_max(int id, float min, float max); |
59 |
ros::Subscriber joint_state_subscriber; |
60 |
ros::Publisher target_publisher; |
61 |
|
62 |
|
63 |
double get_timestamp_ms();
|
64 |
double target_angle[ICUB_JOINT_ID_ENUM_SIZE];
|
65 |
double target_angle_previous[ICUB_JOINT_ID_ENUM_SIZE];
|
66 |
|
67 |
void set_eyelid_angle(double angle); |
68 |
void set_eyebrow_angle(int id); |
69 |
void set_mouth();
|
70 |
|
71 |
//iCubDataReceiver *icub_data_receiver;
|
72 |
void init_joints();
|
73 |
double lid_angle;
|
74 |
int lid_opening_previous;
|
75 |
int previous_mouth_state;
|
76 |
|
77 |
std::string input_scope; |
78 |
std::string output_scope; |
79 |
|
80 |
float last_pos_eye_vergence;
|
81 |
float last_pos_eye_pan;
|
82 |
float last_vel_eye_vergence;
|
83 |
float last_vel_eye_pan;
|
84 |
|
85 |
void store_joint(int id, float value); |
86 |
void set_target_in_positionmode(int id, double value); |
87 |
void set_target_in_velocitymode(int id, double value); |
88 |
|
89 |
|
90 |
int convert_enum_to_motorid(int e); |
91 |
int convert_motorid_to_enum(int id); |
92 |
|
93 |
|
94 |
typedef boost::bimap<int, int > enum_id_bimap_t; |
95 |
typedef enum_id_bimap_t::value_type enum_id_bimap_entry_t;
|
96 |
enum_id_bimap_t enum_id_bimap; |
97 |
}; |