Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / include / mekajointinterface.h @ d82702d2

History | View | Annotate | Download (1.998 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 473a6a6c Simon Schulz
#include "ros/ros.h"
8
#include "sensor_msgs/JointState.h"
9 a4795834 Simon Schulz
#include "trajectory_msgs/JointTrajectory.h"
10 2be6243f Sebastian Meyer zu Borgsen
11
class MekaJointInterface : public humotion::server::JointInterface{
12
public:
13 e4bb9fd4 Simon Schulz
    MekaJointInterface(std::string _input_scope, std::string _output_scope);
14 2be6243f Sebastian Meyer zu Borgsen
    ~MekaJointInterface();
15
16
    //void fetch_position(Device *dev, double timestamp);
17
    //void fetch_speed(Device *dev, double timestamp);
18 473a6a6c Simon Schulz
    //void fetch_position(int id, double value, double timestamp);
19
    //void fetch_speed(int id, double value, double timestamp);
20 2be6243f Sebastian Meyer zu Borgsen
    void run();
21
22
    static const int MAIN_LOOP_FREQUENCY = 50;
23
24
protected:
25
    void disable_joint(int e);
26
    void publish_target_position(int e);
27
    void enable_joint(int e);
28
    void execute_motion();
29
30
private:
31 473a6a6c Simon Schulz
    void incoming_jointstates(const sensor_msgs::JointState & msg);
32 a4795834 Simon Schulz
    void store_dummy_data(int id, double timestamp);
33
    void store_min_max(int id, float min, float max);
34 473a6a6c Simon Schulz
    ros::Subscriber joint_state_subscriber;
35 a4795834 Simon Schulz
    ros::Publisher target_publisher;
36 473a6a6c Simon Schulz
37 6353defa Simon Schulz
    double get_timestamp_s();
38 2be6243f Sebastian Meyer zu Borgsen
39
    void set_eyelid_angle(double angle);
40
    void set_eyebrow_angle(int id);
41
    void set_mouth();
42
43
    //iCubDataReceiver *icub_data_receiver;
44
    void init_joints();
45
    double lid_angle;
46
    int lid_opening_previous;
47
    int previous_mouth_state;
48
49 e4bb9fd4 Simon Schulz
    std::string input_scope;
50
    std::string output_scope;
51 2be6243f Sebastian Meyer zu Borgsen
52
    float last_pos_eye_vergence;
53
    float last_pos_eye_pan;
54
    float last_vel_eye_vergence;
55
    float last_vel_eye_pan;
56
57
    void store_joint(int id, float value);
58
    void set_target_in_positionmode(int id, double value);
59
    void set_target_in_velocitymode(int id, double value);
60
61
62
    int convert_enum_to_motorid(int e);
63
    int convert_motorid_to_enum(int id);
64
65
66
    typedef boost::bimap<int, int > enum_id_bimap_t;
67
    typedef enum_id_bimap_t::value_type enum_id_bimap_entry_t;
68
    enum_id_bimap_t enum_id_bimap;
69
};