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