Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / src / mekajointinterface.cpp @ 2be6243f

History | View | Annotate | Download (25.245 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
//! constructor
8
MekaJointInterface::MekaJointInterface(string _scope) : humotion::server::JointInterface(){
9
    scope = _scope;
10
11
    //add mapping from ids to enums:
12
    //this might look strange at the first sight but we need to have a generic
13
    //way to acces joints from libhumotion. therefore the lib uses its enum with ID_* enum ids
14
    //to access the joints. now we need to define a mapping to map those to our motor ids.
15
    //this is what we use the enum bimap for (convertion fro/to motorid is handled
16
    //by \sa convert_enum_to_motorid() and \sa convert_motorid_to_enum() lateron
17
/*
18
    //MOUTH
19
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_UPPER,   ID_LIP_LEFT_UPPER));
20
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_LOWER,   ID_LIP_LEFT_LOWER));
21
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_UPPER, ID_LIP_CENTER_UPPER));
22
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_LOWER, ID_LIP_CENTER_LOWER));
23
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_UPPER,  ID_LIP_RIGHT_UPPER));
24
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_LOWER,  ID_LIP_RIGHT_LOWER));
25

26
    //NECK
27
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_PAN,    ID_NECK_PAN));
28
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_TILT,   ID_NECK_TILT));
29
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_ROLL,   ID_NECK_ROLL));
30

31
    //EYES
32
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LR,   ID_EYES_LEFT_LR));
33
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LR,   ID_EYES_RIGHT_LR));
34
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_BOTH_UD,   ID_EYES_BOTH_UD));
35

36
    //EYELIDS
37
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_LOWER, ID_EYES_LEFT_LID_LOWER));
38
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_UPPER, ID_EYES_LEFT_LID_UPPER));
39
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_BROW, ID_EYES_LEFT_BROW));
40

41
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_LOWER, ID_EYES_RIGHT_LID_LOWER));
42
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_UPPER,ID_EYES_RIGHT_LID_UPPER));
43
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_BROW, ID_EYES_RIGHT_BROW));
44

45
    Property options;
46
    options.put("device", "remote_controlboard");
47
    options.put("local", "/local/head");
48
    options.put("remote", scope+"/head");
49
    dd.open(options);
50

51
    //fetch views:
52
    dd.view(iencs);
53
    dd.view(ipos);
54
    dd.view(ivel);
55
    dd.view(ilimits);
56

57
    if ( (!iencs) || (!ipos) || (!ilimits) || (!ivel)){
58
        printf("> ERROR: failed to open icub views\n");
59
        exit(EXIT_FAILURE);
60
    }
61

62
    int joints;
63

64
    //tell humotion about min/max joint values:
65
    init_joints();
66

67
    iencs->getAxes(&joints);
68
    positions.resize(joints);
69
    velocities.resize(joints);
70
    commands.resize(joints);
71

72
    //set position mode:
73
    if (POSITION_CONTROL){
74
        commands=200000.0;
75
        ipos->setRefAccelerations(commands.data());
76
        ipos->setPositionMode();
77
    }else{
78
        ivel->setVelocityMode();
79
        commands=1000000;
80
        ivel->setRefAccelerations(commands.data());
81
    }
82

83
    //attach to facial expressions:
84
    string emotion_scope = scope + "/face/raw/in";
85
    printf("> opening connection to %s\n", emotion_scope.c_str());
86

87
    for(int i=0; i<4; i++){
88
        //strange, if we use one output port only the first command is executed?! flushing issues?
89
        string emotion_port_out = "/emotionwriter" + to_string(i);
90
        if (!emotion_port[i].open(emotion_port_out.c_str())){
91
            printf("> ERROR: failed to open to %s\n",emotion_port_out.c_str());
92
            exit(EXIT_FAILURE);
93
        }
94
        if (!Network::connect(emotion_port_out.c_str(), emotion_scope.c_str())){
95
            printf("> ERROR: failed to connect emotion ports\n");
96
            exit(EXIT_FAILURE);
97
        }
98
    }
99
    */
100
}
101
102
//! destructor
103
MekaJointInterface::~MekaJointInterface(){
104
}
105
106
/*
107

108
//! conversion table for humotion motor ids to our ids:
109
//! \param enum from JointInterface::JOINT_ID_ENUM
110
//! \return int value of motor id
111
int iCubJointInterface::convert_enum_to_motorid(int e){
112
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
113
    if(it == enum_id_bimap.right.end()) {
114
        //key does not exists, we are not interested in that dataset, return -1
115
        return -1;
116
    }
117
    return it->second;
118
}
119

120

121
//! conversion table for our ids to humotion motor ids:
122
//! \param  int value of motor id
123
//! \return enum from JointInterface::JOINT_ID_ENUM
124
int iCubJointInterface::convert_motorid_to_enum(int id){
125
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
126
    if(it == enum_id_bimap.left.end()) {
127
        //key does not exists, we are not interested in that dataset, return -1
128
        return -1;
129
    }
130
    return it->second;
131
}
132

133
//! special command to set eyelid angle
134
//! \param angle in degrees
135
void iCubJointInterface::set_eyelid_angle(double angle){
136
    if (emotion_port[0].getOutputCount()>0){
137
        //try to set the value based on the upper one
138
        //some guesses from the sim: S30 = 0° / S40 = 10°
139
        int opening = (25.0 + 0.8*angle);
140
        opening = min(48, max(24, opening));
141

142
        if (opening == lid_opening_previous){
143
            //no update necessary
144
            return;
145
        }
146

147
        lid_angle = angle;
148
        lid_opening_previous = opening;
149

150
        char buf[20];
151
        sprintf(buf, "S%2d", opening);
152

153
        //printf("> SETTING EYELID '%s' (%f -> %d)\n",buf,angle,opening);
154
        Bottle &cmd = emotion_port[0].prepare();
155
        cmd.clear();
156
        cmd.addString(buf);
157
        emotion_port[0].write();
158
    }else{
159
        printf("> ERROR: no icub emotion output\n");
160
        exit(EXIT_FAILURE);
161
    }
162
}
163

164
//! special command to set the eyebrow angle
165
//! \param id {0=left, 1=right)
166
//! \param angle in degrees
167
void iCubJointInterface::set_eyebrow_angle(int id){
168
    int port_id;
169
    if (id == ICUB_ID_EYES_LEFT_BROW){
170
        port_id = 1;
171
    }else{
172
        port_id = 2;
173
    }
174

175
    if (emotion_port[port_id].getOutputCount()>0){
176
        double angle = target_angle[id];
177
        int icub_val = 0;
178

179
        //swap rotation direction:
180
        if (id==ICUB_ID_EYES_LEFT_BROW) angle = -angle;
181

182
        //convert to icub representation
183
        if (angle < -20){
184
            icub_val = 1;
185
        }else if (angle<10){
186
            icub_val = 2;
187
        }else if (angle<20){
188
            icub_val = 4;
189
        }else{
190
            icub_val = 8;
191
        }
192

193
        //make sure to update only on new values:
194
        if (icub_val == target_angle_previous[id]){
195
                //no updata necessary
196
                return;
197
        }
198

199
        //store actual value:
200
        target_angle_previous[id] = icub_val;
201

202

203
        string cmd_s;
204
        if (id==ICUB_ID_EYES_LEFT_BROW){
205
            cmd_s = "L0" + to_string(icub_val);
206
        }else{
207
            cmd_s = "R0" + to_string(icub_val);
208
        }
209

210
        printf("> SETTING EYEBROW %d (%f -> %s)\n",id,angle,cmd_s.c_str());
211

212
        Bottle &cmd = emotion_port[port_id].prepare();
213
        cmd.clear();
214
        cmd.addString(cmd_s);
215
        emotion_port[port_id].write();
216
    }else{
217
        printf("> ERROR: no icub emotion output\n");
218
        exit(EXIT_FAILURE);
219
    }
220
}
221

222
void iCubJointInterface::run(){
223
    iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
224
    data_receiver->start();
225
}
226
227
//! set the target position of a joint
228
//! \param enum id of joint
229
//! \param float value
230
void iCubJointInterface::publish_target_position(int e){
231
    //first: convert humotion enum to our enum:
232
    int id = convert_enum_to_motorid(e);
233
    if (id == -1){
234
        return; //we are not interested in that data, so we just return here
235
    }
236
237
    if (id == ICUB_ID_NECK_PAN){
238
        //PAN seems to be swapped
239
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
240
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
241
        //icub handles eyes differently, we have to set pan angle + vergence
242
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
243
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
244
        //printf("EYEDBG %3.2f %3.2f --_> pan %3.2f verg=%3.2f\n",joint_target[ID_EYES_LEFT_LR], joint_target[ID_EYES_RIGHT_LR],pan,vergence);
245
246
        store_joint(ICUB_ID_EYES_PAN, pan);
247
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
248
    }else{
249
        store_joint(id, joint_target[e]);
250
    }
251
}
252
253
254
//! set the target position of a joint
255
//! \param id of joint
256
//! \param float value of position
257
void iCubJointInterface::store_joint(int id, float value){
258
    //printf("> set joint %d = %f\n",id,value);
259
    target_angle[id] = value;
260
    //ipos->positionMove(id, value);
261
}
262
263
//! execute a move in position mode
264
//! \param id of joint
265
//! \param angle
266
void iCubJointInterface::set_target_in_positionmode(int id, double value){
267
    if (id>ICUB_ID_EYES_VERGENCE){
268
        printf("> ERROR: set_target_positionmode(id=%d, %3.2f) not supported for this id\n",id,value);
269
        return;
270
    }
271
#if 0
272
    //set speed cacluated as in velocity + set position -> replicates smoothmotion from flobi?!
273

274
    //first: calculate necessary speed to reach the given target within the next clock tick:
275
    double distance = value - target_angle_previous[id];
276
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
277
    //calculate speed for that:
278
    double speed = 0.85 * distance * ((double)MAIN_LOOP_FREQUENCY);
279

280
    //set up speed for controller:
281
    ipos->setRefSpeed(id, speed);
282
#endif
283
    //execute motion
284
    ipos->positionMove(id, value);
285
}
286
287
//! execute a move in velocity mode
288
//! \param id of joint
289
//! \param angle
290
void iCubJointInterface::set_target_in_velocitymode(int id, double value){
291
    //first: calculate necessary speed to reach the given target within the next clock tick:
292
    double distance = value - target_angle_previous[id];
293
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
294
    distance = 0.85 * distance;
295
    //calculate speed
296
    double speed = distance * ((double)MAIN_LOOP_FREQUENCY);
297
    //execute:
298
    ivel->velocityMove(id, speed);
299
    //if (id == ICUB_ID_NECK_PAN) printf("> VEL now=%3.2f target=%3.2f --> dist=%3.2f speed=%3.2f\n",target_angle_previous[id],value,distance,speed);
300
301
    target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value();
302
}
303
304
//! actually execute the scheduled motion commands
305
void iCubJointInterface::execute_motion(){
306
307
    // set up neck and eye motion commands:
308
    if (POSITION_CONTROL){
309
        //position control
310
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
311
            set_target_in_positionmode(i, target_angle[i]);
312
        }
313
    }else{
314
        //velocity control
315
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
316
            set_target_in_velocitymode(i, target_angle[i]);
317
        }
318
    }
319
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
320
321
322
    //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
323
    set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
324
325
    //eyebrows are set using a special command as well:
326
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
327
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
328
329
    //mouth
330
    set_mouth();
331
332
333
}
334
335
void iCubJointInterface::set_mouth(){
336
    //convert from 6DOF mouth displacement to icub leds:
337
    int led_value = 0;
338
339
    //fetch center opening:
340
    double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
341
    bool mouth_open = (center_opening>15.0)?true:false;
342
343
    //side of mouth high or low?
344
    double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0;
345
    double left_avg   = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0;
346
    double right_avg  = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0;
347
348
    //happy, neutral or sad?
349
    double diff_l = center_avg - left_avg;
350
    double diff_r = center_avg - right_avg;
351
    double diff   = (diff_l+diff_r)/2.0;
352
353
    if (diff > 2.0){
354
        if (mouth_open){
355
            led_value = 0x14;
356
        }else{
357
            if (diff > 2.6){
358
                led_value = 0x0A;
359
            }else{
360
                led_value = 0x0B;
361
            }
362
        }
363
    }else if (diff < -3.0){
364
        if (mouth_open){
365
            led_value = 0x06;
366
        }else{
367
            led_value = 0x18;
368
        }
369
    }else if (diff < -2.0){
370
        if (mouth_open){
371
            led_value = 0x04; //0x25;
372
        }else{
373
            led_value = 0x08;
374
        }
375
    }else{
376
        if (mouth_open){
377
            led_value = 0x16;
378
        }else{
379
            led_value = 0x08;
380
        }
381
    }
382
383
384
    if (led_value == previous_mouth_state){
385
        //no update necessary
386
        return;
387
    }
388
389
    previous_mouth_state = led_value;
390
391
    //convert to string:
392
    char buf[10];
393
    sprintf(buf, "M%02X",led_value);
394
395
    /*printf("> sending mouth '%s'\n",buf);
396
    printf("> mouth angles: %3.2f %3.2f %3.2f\n",target_angle[ICUB_ID_LIP_LEFT_UPPER],target_angle[ICUB_ID_LIP_CENTER_UPPER],target_angle[ICUB_ID_LIP_RIGHT_UPPER]);
397
    printf("  mouth         %3.2f %3.2f %3.2f\n",target_angle[ICUB_ID_LIP_LEFT_LOWER],target_angle[ICUB_ID_LIP_CENTER_LOWER],target_angle[ICUB_ID_LIP_RIGHT_LOWER]);
398
    printf("  mouth  open=%3.2f diff=%3.2f\n", center_opening, diff);*/
399
400
    //add mouth:
401
    Bottle &cmd = emotion_port[3].prepare();
402
    cmd.clear();
403
    cmd.addString(buf);
404
    emotion_port[3].write();
405
406
407
    //store joint values which we do not handle on icub here:
408
    double timestamp = get_timestamp_ms();
409
    JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER,   target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp);
410
    JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER,   target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp);
411
    JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp);
412
    JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp);
413
    JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER,  target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp);
414
    JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER,  target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp);
415
416
}
417
418
double iCubJointInterface::get_timestamp_ms(){
419
    struct timespec spec;
420
    clock_gettime(CLOCK_REALTIME, &spec);
421
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
422
}
423
424
//! set the current position of a joint
425
//! \param id of joint
426
//! \param float value of position
427
//! \param double timestamp
428
void iCubJointInterface::fetch_position(int id, double value, double timestamp){
429
    //store joint based on id:
430
    switch(id){
431
        default:
432
            printf("> ERROR: unhandled joint id %d\n",id);
433
            return;
434
435
        case(100):
436
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp);
437
            break;
438
439
        case(2):
440
            //PAN is inverted!
441
            JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp);
442
            break;
443
444
        case(0):
445
            JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp);
446
            break;
447
448
        case(1):
449
            JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp);
450
            break;
451
452
        case(3):
453
            JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp);
454
            break;
455
456
        //icub handles eyes differently, we have to set pan angle + vergence
457
        case(4): {//pan
458
            last_pos_eye_pan = value;
459
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
460
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
461
462
            //printf("> eye: pan=%3.2f vergence=%3.2f --> L=%3.2f R=%3.2f\n", last_pos_eye_pan, last_pos_eye_vergence, left, right);
463
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
464
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
465
            break;
466
        }
467
468
        case(5): { //vergence
469
            last_pos_eye_vergence = value;
470
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
471
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
472
473
            //printf("> eye: pan=%3.2f vergence=%3.2f --> L=%3.2f R=%3.2f\n", last_pos_eye_pan, last_pos_eye_vergence, left, right);
474
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
475
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
476
            break;
477
        }
478
    }
479
480
481
}
482
483
//! set the current speed of a joint
484
//! \param enum id of joint
485
//! \param float value of speed
486
//! \param double timestamp
487
void iCubJointInterface::fetch_speed(int id, double value, double timestamp){
488
489
    switch(id){
490
        default:
491
            printf("> ERROR: unhandled joint id %d\n",id);
492
            return;
493
494
        case(2):
495
            JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp);
496
            break;
497
498
        case(0):
499
            JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp);
500
            break;
501
502
        case(1):
503
            JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp);
504
            break;
505
506
        case(3):
507
            JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp);
508
            break;
509
510
        //icub handles eyes differently, we have to set pan angle + vergence
511
        case(4): {//pan
512
            last_vel_eye_pan = value;
513
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
514
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
515
516
            //printf("> eye: velocity pan=%3.2f vergence=%3.2f --> L=%3.2f R=%3.2f\n", last_vel_eye_pan, last_vel_eye_vergence, left, right);
517
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
518
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
519
            break;
520
        }
521
522
        case(5): { //vergence
523
            last_vel_eye_pan = value;
524
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
525
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
526
527
            //printf("> eye: velocity pan=%3.2f vergence=%3.2f --> L=%3.2f R=%3.2f\n", last_vel_eye_pan, last_vel_eye_vergence, left, right);
528
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
529
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
530
            break;
531
        }
532
    }
533
/*
534
    JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
535
    JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
536
    JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
537
    JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
538
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
539
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
540

541
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_LOWER, 0.0, timestamp);
542
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_UPPER, 0.0, timestamp);
543
    JointInterface::store_incoming_speed(ID_EYES_LEFT_BROW, 0.0, timestamp);
544

545
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_LOWER, 0.0, timestamp);
546
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_UPPER,0.0, timestamp);
547
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_BROW, 0.0, timestamp);*/
548
    /*
549
    //fetch enum id:
550
    int e = convert_motorid_to_enum(device->get_device_id());
551
    if (e == -1){
552
        return; //we are not interested in that data, so we just return here
553
    }
554

555
    JointInterface::store_incoming_speed(e, device->get_register(XSC3_REGISTER_MOTORSPEED), timestamp);*/
556
557
}
558
/*
559
//! conversion table for humotion motor ids to our ids:
560
//! \param enum from JointInterface::JOINT_ID_ENUM
561
//! \return int value of motor id
562
int HumotionJointInterface::convert_enum_to_motorid(int e){
563
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
564
    if(it == enum_id_bimap.right.end()) {
565
        //key does not exists, we are not interested in that dataset, return -1
566
        return -1;
567
    }
568

569
    return it->second;
570
}
571

572

573
//! conversion table for our ids to humotion motor ids:
574
//! \param  int value of motor id
575
//! \return enum from JointInterface::JOINT_ID_ENUM
576
int HumotionJointInterface::convert_motorid_to_enum(int id){
577
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
578
    if(it == enum_id_bimap.left.end()) {
579
        //key does not exists, we are not interested in that dataset, return -1
580
        return -1;
581
    }
582

583
    return it->second;
584
}
585
*/
586
587
//! prepare and enable a joint
588
//! NOTE: this should also prefill the min/max positions for this joint
589
//! \param the enum id of a joint
590
void iCubJointInterface::enable_joint(int e){
591
    //FIXME ADD THIS:
592
    // enable the amplifier and the pid controller on each joint
593
    /*for (i = 0; i < nj; i++) {
594
       amp->enableAmp(i);
595
       pid->enablePid(i);
596
    }*/
597
598
599
    //set up smooth motion controller
600
    //step1: set up framerate
601
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
602
603
    //step2: set controllertype:
604
    //printf("> activating smooth motion control for joint id 0x%02X (%s)\n", motor_id, joint_name.c_str());
605
    //dev->set_register_blocking(XSC3_REGISTER_PID_CONTROLLER, XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK, true);
606
607
    //step3: set pid controller:
608
    /*if ((e == ID_LIP_LEFT_UPPER) || (e == ID_LIP_LEFT_LOWER) || (e == ID_LIP_CENTER_UPPER) || (e == ID_LIP_CENTER_LOWER) || (e == ID_LIP_RIGHT_UPPER) || (e == ID_LIP_RIGHT_LOWER)){
609
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
610
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
611
    }*/
612
613
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
614
615
    //check if setting pid controllertype was successfull:
616
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
617
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
618
        exit(1);
619
    }*/
620
621
    //fetch min/max:
622
   // init_joint(e);
623
624
    //ok fine, now enable motor:
625
    //printf("> enabling motor %s\n", joint_name.c_str());
626
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
627
628
}
629
630
void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){
631
    double min, max;
632
    ilimits->getLimits(id, &min, &max);
633
    joint_min[e] = min;
634
    joint_max[e] = max;
635
}
636
637
//! initialise a joint (set up controller mode etc)
638
//! \param joint enum
639
void iCubJointInterface::init_joints(){
640
    store_min_max(ilimits, 0, ID_NECK_TILT);
641
    store_min_max(ilimits, 1, ID_NECK_ROLL);
642
    store_min_max(ilimits, 2, ID_NECK_PAN);
643
    store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
644
645
    //icub handles eyes differently, we have to set pan angle + vergence
646
    double pan_min, pan_max, vergence_min, vergence_max;
647
    ilimits->getLimits(4, &pan_min, &pan_max);
648
    ilimits->getLimits(5, &vergence_min, &vergence_max);
649
650
    //this is not 100% correct, should be fixed:
651
    joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
652
    joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
653
    joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR];
654
    joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR];
655
656
    //eyelids:
657
    joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30;
658
    joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30;
659
    lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
660
661
    //eyebrows:
662
    joint_min[ID_EYES_LEFT_BROW] = -50;
663
    joint_max[ID_EYES_LEFT_BROW] = 50;
664
    joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW];
665
    joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW];
666
667
    //mouth:
668
    joint_min[ID_LIP_CENTER_UPPER] = 5;
669
    joint_max[ID_LIP_CENTER_UPPER] = 50;
670
    joint_min[ID_LIP_CENTER_LOWER] = 5;
671
    joint_max[ID_LIP_CENTER_LOWER] = 50;
672
    joint_min[ID_LIP_LEFT_UPPER] = 5;
673
    joint_max[ID_LIP_LEFT_UPPER] = 50;
674
    joint_min[ID_LIP_LEFT_LOWER] = 5;
675
    joint_max[ID_LIP_LEFT_LOWER] = 50;
676
    joint_min[ID_LIP_RIGHT_UPPER] = 5;
677
    joint_max[ID_LIP_RIGHT_UPPER] = 50;
678
    joint_min[ID_LIP_RIGHT_LOWER] = 5;
679
    joint_max[ID_LIP_RIGHT_LOWER] = 50;
680
681
682
}
683
684
//! shutdown and disable a joint
685
//! \param the enum id of a joint
686
void iCubJointInterface::disable_joint(int e){
687
    /*
688
        //first: convert humotion enum to our enum:
689
        int motor_id = convert_enum_to_motorid(e);
690
        if (motor_id == -1){
691
            return; //we are not interested in that data, so we just return here
692
        }
693

694
        //fetch device:
695
        Device *dev = get_device(motor_id);
696
        printf("> FIXME: ADD DISABLE CODE\n");
697
        printf("> FIXME: ADD DISABLE CODE\n");
698
        printf("> FIXME: ADD DISABLE CODE\n");
699
        printf("> FIXME: ADD DISABLE CODE\n");
700
        printf("> FIXME: ADD DISABLE CODE\n");
701
        printf("> FIXME: ADD DISABLE CODE\n");
702
        printf("> FIXME: ADD DISABLE CODE\n");
703
        printf("> FIXME: ADD DISABLE CODE\n");
704
        printf("> FIXME: ADD DISABLE CODE\n");
705
        */
706
}