Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / src / mekajointinterface.cpp @ 54d38c01

History | View | Annotate | Download (7.481 KB)

1 2be6243f Sebastian Meyer zu Borgsen
#include "mekajointinterface.h"
2
using namespace std;
3
4
//WARNING: DO NOT CHANGE THIS; VELOCITYMODE IS NOT YET IMPLEMENTED
5
#define POSITION_CONTROL 1
6
7 473a6a6c Simon Schulz
void MekaJointInterface::incoming_jointstates(const sensor_msgs::JointState & msg){
8 a4795834 Simon Schulz
    //fetch current timestamp
9 6353defa Simon Schulz
    double timestamp = msg.header.stamp.toSec();
10 a4795834 Simon Schulz
11
    //iterate through incoming joints and filter out joints we need:
12
    for(int i=0; i<msg.name.size(); i++){
13 6353defa Simon Schulz
14 a4795834 Simon Schulz
        string name = msg.name[i];
15 0b76d42b Simon Schulz
        //printf("incoming data for joint '%s'\n", name.c_str());
16 a4795834 Simon Schulz
17
        int id = -1;
18 e8e20dfe Sebastian Meyer zu Borgsen
        if (name == "head_j1"){
19 a4795834 Simon Schulz
            id = ID_NECK_PAN;
20 e8e20dfe Sebastian Meyer zu Borgsen
        }else if(name == "head_j0"){
21 a4795834 Simon Schulz
            id = ID_NECK_TILT;
22
        }
23
24
        //store data:
25
        if (id != -1){
26
            //printf("> storing joint data for joint id %d\n", id);
27 7115c3a4 Simon Schulz
            if (i >= msg.position.size()){
28 2c4bbc89 Simon Schulz
                printf("> joint state msg is missing position data for joint '%s'...\n", name.c_str());
29
                return;
30 7115c3a4 Simon Schulz
            }
31
            if (i >= msg.velocity.size()){
32 2c4bbc89 Simon Schulz
                //printf("> joint state msg is missing velocity data for joint '%s'...\n", name.c_str());
33 3f8fb5a1 Simon Schulz
                //exit(EXIT_FAILURE);
34 2c4bbc89 Simon Schulz
                return;
35 7115c3a4 Simon Schulz
            }
36
            //ok, safe to access data
37 b0d48d96 Sebastian Meyer zu Borgsen
            if (id == ID_NECK_PAN){
38
                //joint is inverted
39
                JointInterface::store_incoming_position(id, -180.0 / M_PI * msg.position[i], timestamp);
40
                JointInterface::store_incoming_speed(   id, -180.0 / M_PI * msg.velocity[i], timestamp);
41
            }else if (id == ID_NECK_TILT){
42
                JointInterface::store_incoming_position(id, 180.0 / M_PI * msg.position[i], timestamp);
43
                JointInterface::store_incoming_speed(   id, 180.0 / M_PI * msg.velocity[i], timestamp);
44
            }
45 a4795834 Simon Schulz
        }
46
    }
47
48 6353defa Simon Schulz
    //dummy data uses current time
49
    timestamp = get_timestamp_s();
50
51 a4795834 Simon Schulz
    //store dummy positions for joints we do not know about:
52
    store_dummy_data(ID_LIP_LEFT_UPPER, timestamp);
53
    store_dummy_data(ID_LIP_LEFT_LOWER, timestamp);
54
    store_dummy_data(ID_LIP_CENTER_UPPER, timestamp);
55
    store_dummy_data(ID_LIP_CENTER_LOWER, timestamp);
56
    store_dummy_data(ID_LIP_RIGHT_UPPER, timestamp);
57
    store_dummy_data(ID_LIP_RIGHT_LOWER, timestamp);
58
59
    store_dummy_data(ID_NECK_ROLL, timestamp);
60
    store_dummy_data(ID_EYES_BOTH_UD, timestamp);
61
    store_dummy_data(ID_EYES_LEFT_LR, timestamp);
62
    store_dummy_data(ID_EYES_RIGHT_LR, timestamp);
63
    store_dummy_data(ID_EYES_LEFT_LID_LOWER, timestamp);
64
    store_dummy_data(ID_EYES_LEFT_LID_UPPER, timestamp);
65
    store_dummy_data(ID_EYES_LEFT_BROW, timestamp);
66
    store_dummy_data(ID_EYES_RIGHT_LID_LOWER, timestamp);
67
    store_dummy_data(ID_EYES_RIGHT_LID_UPPER, timestamp);
68
    store_dummy_data(ID_EYES_RIGHT_BROW, timestamp);
69
70
}
71
72
void MekaJointInterface::store_dummy_data(int id, double timestamp){
73 fcc5e139 Sebastian Meyer zu Borgsen
    JointInterface::store_incoming_position(id, 0.0, timestamp);
74 a4795834 Simon Schulz
    JointInterface::store_incoming_speed(id, 0.0, timestamp);
75 473a6a6c Simon Schulz
}
76
77 2be6243f Sebastian Meyer zu Borgsen
//! constructor
78 e4bb9fd4 Simon Schulz
MekaJointInterface::MekaJointInterface(string _input_scope, string _output_scope) : humotion::server::JointInterface(){
79
    input_scope = _input_scope;
80
    output_scope = _output_scope;
81 2be6243f Sebastian Meyer zu Borgsen
82 473a6a6c Simon Schulz
    //subscribe to meka joint states
83 99ebae32 Simon Schulz
    int argc = 0;
84
    ros::init(argc, (char**)NULL, "meka_humotion");
85 473a6a6c Simon Schulz
    ros::NodeHandle n;
86 2be6243f Sebastian Meyer zu Borgsen
87 e4bb9fd4 Simon Schulz
    printf("> listening on jointstates on '%s'\n",input_scope.c_str());
88
    joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates , this);
89 2be6243f Sebastian Meyer zu Borgsen
90 e4bb9fd4 Simon Schulz
    printf("> sending targets on '%s'\n", output_scope.c_str());
91
    target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
92 2be6243f Sebastian Meyer zu Borgsen
93 a4795834 Simon Schulz
    //tell humotion about min/max joint values:
94
    init_joints();
95 2be6243f Sebastian Meyer zu Borgsen
}
96
97
//! destructor
98
MekaJointInterface::~MekaJointInterface(){
99
}
100
101 473a6a6c Simon Schulz
102
103
void MekaJointInterface::run(){
104 a4795834 Simon Schulz
   ros::spin();
105 473a6a6c Simon Schulz
}
106
107
108 6353defa Simon Schulz
double MekaJointInterface::get_timestamp_s(){
109 a4795834 Simon Schulz
    struct timespec spec;
110
    clock_gettime(CLOCK_REALTIME, &spec);
111 6353defa Simon Schulz
    return spec.tv_sec + spec.tv_nsec / 1.0e9;
112 a4795834 Simon Schulz
}
113
114 473a6a6c Simon Schulz
//! set the target position of a joint
115
//! \param enum id of joint
116
//! \param float value
117
void MekaJointInterface::publish_target_position(int e){
118 6353defa Simon Schulz
   //we do this in execute motion for all joints at once...
119 473a6a6c Simon Schulz
}
120
121
122
//! actually execute the scheduled motion commands
123
void MekaJointInterface::execute_motion(){
124 a4795834 Simon Schulz
    //build msg
125
    trajectory_msgs::JointTrajectory msg;
126
    msg.joint_names.push_back("head_j0");
127
    msg.joint_names.push_back("head_j1");
128
129 e8e20dfe Sebastian Meyer zu Borgsen
    trajectory_msgs::JointTrajectoryPoint p;
130
    p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0);
131 f10ec142 Sebastian Meyer zu Borgsen
    //pan joint is inverted!
132
    p.positions.push_back(-joint_target[ID_NECK_PAN] * M_PI / 180.0);
133 fcc5e139 Sebastian Meyer zu Borgsen
    //printf("targets pan=%4.1f tilt=%4.1f (eye p %4.1f t %4.2f)\n",joint_target[ID_NECK_TILT],joint_target[ID_NECK_PAN],joint_target[ID_EYES_LEFT_LR],joint_target[ID_EYES_BOTH_UD]);
134 a4795834 Simon Schulz
135 e8e20dfe Sebastian Meyer zu Borgsen
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
136 a4795834 Simon Schulz
137 e8e20dfe Sebastian Meyer zu Borgsen
    msg.points.push_back(p);
138 a4795834 Simon Schulz
139
    target_publisher.publish(msg);
140
141
    /*
142
     void MekaJointInterface::store_min_max(int id, float min, float max){
143
header:
144
  seq: 636
145
  stamp:
146
    secs: 0
147
    nsecs: 0
148
  frame_id: ''
149
joint_names: ['head_j0', 'head_j1']
150
points:
151
  -
152
    positions: [-0.31, 0.01954768762234005]
153
    velocities: []
154
    accelerations: []
155
    effort: []
156
    time_from_start:
157
      secs: 1
158
      nsecs: 0
159

160
     */
161
162 473a6a6c Simon Schulz
    #if 0
163
    // set up neck and eye motion commands:
164
    if (POSITION_CONTROL){
165
        //position control
166
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
167
            set_target_in_positionmode(i, target_angle[i]);
168
        }
169
    }else{
170
        //velocity control
171
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
172
            set_target_in_velocitymode(i, target_angle[i]);
173
        }
174
    }
175
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
176

177

178
    //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
179
    set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
180

181
    //eyebrows are set using a special command as well:
182
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
183
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
184

185
    //mouth
186
    set_mouth();
187

188
    #endif
189
}
190

191

192
//! prepare and enable a joint
193
//! NOTE: this should also prefill the min/max positions for this joint
194
//! \param the enum id of a joint
195
void MekaJointInterface::enable_joint(int e){
196 ddccf279 Simon Schulz
    //meka does not support this, joints are always enabled
197 473a6a6c Simon Schulz
}
198

199
//! shutdown and disable a joint
200
//! \param the enum id of a joint
201
void MekaJointInterface::disable_joint(int e){
202 ddccf279 Simon Schulz
    //meka does not support this, joints are always enabled
203 473a6a6c Simon Schulz
}
204

205 a4795834 Simon Schulz
void MekaJointInterface::store_min_max(int id, float min, float max){
206
    joint_min[id] = min;
207
    joint_max[id] = max;
208
}
209

210
void MekaJointInterface::init_joints(){
211 f10ec142 Sebastian Meyer zu Borgsen
    store_min_max(ID_NECK_TILT, -37, 1);
212
    store_min_max(ID_NECK_PAN, -70, 70);
213 a4795834 Simon Schulz

214
    store_min_max(ID_NECK_ROLL, -1, 1);
215
    store_min_max(ID_EYES_BOTH_UD, -1, 1);
216
    store_min_max(ID_EYES_LEFT_LR, -1, 1);
217
    store_min_max(ID_EYES_RIGHT_LR, -1, 1);
218
    store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1);
219
    store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1);
220
    store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1);
221
    store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1);
222
    store_min_max(ID_EYES_LEFT_BROW, -1, 1);
223
    store_min_max(ID_EYES_RIGHT_BROW, -1, 1);
224
    store_min_max(ID_LIP_CENTER_UPPER, -1, 1);
225
    store_min_max(ID_LIP_CENTER_LOWER, -1, 1);
226
    store_min_max(ID_LIP_LEFT_UPPER, -1, 1);
227
    store_min_max(ID_LIP_LEFT_LOWER, -1, 1);
228
    store_min_max(ID_LIP_RIGHT_UPPER, -1, 1);
229
    store_min_max(ID_LIP_RIGHT_LOWER, -1, 1);
230
}
231