Statistics
| Branch: | Tag: | Revision:

humotion / examples / yarp_icub / src / icub_jointinterface.cpp @ fe5a9426

History | View | Annotate | Download (25.746 KB)

1
#include "icub_jointinterface.h"
2
#include <yarp/os/Property.h>
3
using namespace yarp::dev;
4
using namespace yarp::sig;
5
using namespace yarp::os;
6
using namespace std;
7
/*running:
8
/media/local_data/sschulz/iros15/icub-nightly/share/iCub/contexts/simConfig:> iCub_SIM
9
/media/local_data/sschulz/iros15/icub-nightly/share/iCub/contexts/simFaceExpressions:> ../../../../bin/simFaceExpressions
10
yarp connect /face/eyelids /icubSim/face/eyelids
11
yarp connect /face/image/out /icubSim/texture/face
12

13
TEST: yarp write /writer /icubSim/face/raw/in
14

15
http://wiki.icub.org/wiki/Motor_control
16
*/
17

    
18
//WARNING: DO NOT CHANGE THIS; VELOCITYMODE IS NOT YET IMPLEMENTED
19
#define POSITION_CONTROL 1
20

    
21

    
22
//! constructor
23
iCubJointInterface::iCubJointInterface(string _scope) : humotion::server::JointInterface(){
24
    scope = _scope;
25

    
26

    
27
    //add mapping from ids to enums:
28
    //this might look strange at the first sight but we need to have a generic
29
    //way to acces joints from libhumotion. therefore the lib uses its enum with ID_* enum ids
30
    //to access the joints. now we need to define a mapping to map those to our motor ids.
31
    //this is what we use the enum bimap for (convertion fro/to motorid is handled
32
    //by \sa convert_enum_to_motorid() and \sa convert_motorid_to_enum() lateron
33

    
34
    //MOUTH
35
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_UPPER,   ID_LIP_LEFT_UPPER));
36
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_LOWER,   ID_LIP_LEFT_LOWER));
37
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_UPPER, ID_LIP_CENTER_UPPER));
38
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_LOWER, ID_LIP_CENTER_LOWER));
39
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_UPPER,  ID_LIP_RIGHT_UPPER));
40
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_LOWER,  ID_LIP_RIGHT_LOWER));
41

    
42
    //NECK
43
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_PAN,    ID_NECK_PAN));
44
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_TILT,   ID_NECK_TILT));
45
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_ROLL,   ID_NECK_ROLL));
46

    
47
    //EYES
48
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LR,   ID_EYES_LEFT_LR));
49
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LR,   ID_EYES_RIGHT_LR));
50
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_BOTH_UD,   ID_EYES_BOTH_UD));
51

    
52
    //EYELIDS
53
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_LOWER, ID_EYES_LEFT_LID_LOWER));
54
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_UPPER, ID_EYES_LEFT_LID_UPPER));
55
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_BROW, ID_EYES_LEFT_BROW));
56

    
57
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_LOWER, ID_EYES_RIGHT_LID_LOWER));
58
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_UPPER,ID_EYES_RIGHT_LID_UPPER));
59
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_BROW, ID_EYES_RIGHT_BROW));
60

    
61
    Property options;
62
    options.put("device", "remote_controlboard");
63
    options.put("local", "/local/head");
64
    options.put("remote", scope+"/head");
65
    dd.open(options);
66

    
67
    //fetch views:
68
    dd.view(iencs);
69
    dd.view(ipos);
70
    dd.view(ivel);
71
    dd.view(ilimits);
72

    
73
    if ( (!iencs) || (!ipos) || (!ilimits) || (!ivel)){
74
        printf("> ERROR: failed to open icub views\n");
75
        exit(EXIT_FAILURE);
76
    }
77

    
78
    int joints;
79

    
80
    //tell humotion about min/max joint values:
81
    init_joints();
82

    
83
    iencs->getAxes(&joints);
84
    positions.resize(joints);
85
    velocities.resize(joints);
86
    commands.resize(joints);
87

    
88
    //set position mode:
89
    if (POSITION_CONTROL){
90
        commands=200000.0;
91
        ipos->setRefAccelerations(commands.data());
92
        ipos->setPositionMode();
93
    }else{
94
        ivel->setVelocityMode();
95
        commands=1000000;
96
        ivel->setRefAccelerations(commands.data());
97
    }
98

    
99
    //attach to facial expressions:
100
    string emotion_scope = scope + "/face/raw/in";
101
    printf("> opening connection to %s\n", emotion_scope.c_str());
102

    
103
    for(int i=0; i<4; i++){
104
        //strange, if we use one output port only the first command is executed?! flushing issues?
105
        string emotion_port_out = "/emotionwriter" + to_string(i);
106
        if (!emotion_port[i].open(emotion_port_out.c_str())){
107
            printf("> ERROR: failed to open to %s\n",emotion_port_out.c_str());
108
            exit(EXIT_FAILURE);
109
        }
110
        if (!Network::connect(emotion_port_out.c_str(), emotion_scope.c_str())){
111
            printf("> ERROR: failed to connect emotion ports\n");
112
            exit(EXIT_FAILURE);
113
        }
114
    }
115
}
116

    
117
//! destructor
118
iCubJointInterface::~iCubJointInterface(){
119
}
120

    
121

    
122

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

    
135

    
136
//! conversion table for our ids to humotion motor ids:
137
//! \param  int value of motor id
138
//! \return enum from JointInterface::JOINT_ID_ENUM
139
int iCubJointInterface::convert_motorid_to_enum(int id){
140
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
141
    if(it == enum_id_bimap.left.end()) {
142
        //key does not exists, we are not interested in that dataset, return -1
143
        return -1;
144
    }
145
    return it->second;
146
}
147

    
148
//! special command to set eyelid angle
149
//! \param angle in degrees
150
void iCubJointInterface::set_eyelid_angle(double angle){
151
    if (emotion_port[0].getOutputCount()>0){
152
        //try to set the value based on the upper one
153
        //some guesses from the sim: S30 = 0° / S40 = 10°
154
        int opening = (25.0 + 0.8*angle);
155
        opening = min(48, max(24, opening));
156

    
157
        if (opening == lid_opening_previous){
158
            //no update necessary
159
            return;
160
        }
161

    
162
        lid_angle = angle;
163
        lid_opening_previous = opening;
164

    
165
        char buf[20];
166
        sprintf(buf, "S%2d", opening);
167

    
168
        //printf("> SETTING EYELID '%s' (%f -> %d)\n",buf,angle,opening);
169
        Bottle &cmd = emotion_port[0].prepare();
170
        cmd.clear();
171
        cmd.addString(buf);
172
        emotion_port[0].write();
173
    }else{
174
        printf("> ERROR: no icub emotion output\n");
175
        exit(EXIT_FAILURE);
176
    }
177
}
178

    
179
//! special command to set the eyebrow angle
180
//! \param id {0=left, 1=right)
181
//! \param angle in degrees
182
void iCubJointInterface::set_eyebrow_angle(int id){
183
    int port_id;
184
    if (id == ICUB_ID_EYES_LEFT_BROW){
185
        port_id = 1;
186
    }else{
187
        port_id = 2;
188
    }
189

    
190
    if (emotion_port[port_id].getOutputCount()>0){
191
        double angle = target_angle[id];
192
        int icub_val = 0;
193

    
194
        //swap rotation direction:
195
        if (id==ICUB_ID_EYES_LEFT_BROW) angle = -angle;
196

    
197
        //convert to icub representation
198
        if (angle < -20){
199
            icub_val = 1;
200
        }else if (angle<10){
201
            icub_val = 2;
202
        }else if (angle<20){
203
            icub_val = 4;
204
        }else{
205
            icub_val = 8;
206
        }
207

    
208
        //make sure to update only on new values:
209
        if (icub_val == target_angle_previous[id]){
210
                //no updata necessary
211
                return;
212
        }
213

    
214
        //store actual value:
215
        target_angle_previous[id] = icub_val;
216

    
217

    
218
        string cmd_s;
219
        if (id==ICUB_ID_EYES_LEFT_BROW){
220
            cmd_s = "L0" + to_string(icub_val);
221
        }else{
222
            cmd_s = "R0" + to_string(icub_val);
223
        }
224

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

    
227
        Bottle &cmd = emotion_port[port_id].prepare();
228
        cmd.clear();
229
        cmd.addString(cmd_s);
230
        emotion_port[port_id].write();
231
    }else{
232
        printf("> ERROR: no icub emotion output\n");
233
        exit(EXIT_FAILURE);
234
    }
235
}
236

    
237
void iCubJointInterface::run(){
238
    iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
239
    data_receiver->start();
240
}
241

    
242
//! set the target position of a joint
243
//! \param enum id of joint
244
//! \param float value
245
void iCubJointInterface::publish_target_position(int e){
246
    //first: convert humotion enum to our enum:
247
    int id = convert_enum_to_motorid(e);
248
    if (id == -1){
249
        return; //we are not interested in that data, so we just return here
250
    }
251

    
252
    if (id == ICUB_ID_NECK_PAN){
253
        //PAN seems to be swapped
254
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
255
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
256
        //icub handles eyes differently, we have to set pan angle + vergence
257
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
258
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
259
        //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);
260

    
261
        store_joint(ICUB_ID_EYES_PAN, pan);
262
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
263
    }else{
264
        store_joint(id, joint_target[e]);
265
    }
266
}
267

    
268

    
269
//! set the target position of a joint
270
//! \param id of joint
271
//! \param float value of position
272
void iCubJointInterface::store_joint(int id, float value){
273
    //printf("> set joint %d = %f\n",id,value);
274
    target_angle[id] = value;
275
    //ipos->positionMove(id, value);
276
}
277

    
278
//! execute a move in position mode
279
//! \param id of joint
280
//! \param angle
281
void iCubJointInterface::set_target_in_positionmode(int id, double value){
282
    if (id>ICUB_ID_EYES_VERGENCE){
283
        printf("> ERROR: set_target_positionmode(id=%d, %3.2f) not supported for this id\n",id,value);
284
        return;
285
    }
286
#if 0
287
    //set speed cacluated as in velocity + set position -> replicates smoothmotion from flobi?!
288

289
    //first: calculate necessary speed to reach the given target within the next clock tick:
290
    double distance = value - target_angle_previous[id];
291
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
292
    //calculate speed for that:
293
    double speed = 0.85 * distance * ((double)MAIN_LOOP_FREQUENCY);
294

295
    //set up speed for controller:
296
    ipos->setRefSpeed(id, speed);
297
#endif
298
    //execute motion
299
    ipos->positionMove(id, value);
300
}
301

    
302
//! execute a move in velocity mode
303
//! \param id of joint
304
//! \param angle
305
void iCubJointInterface::set_target_in_velocitymode(int id, double value){
306
    //first: calculate necessary speed to reach the given target within the next clock tick:
307
    double distance = value - target_angle_previous[id];
308
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
309
    distance = 0.85 * distance;
310
    //calculate speed
311
    double speed = distance * ((double)MAIN_LOOP_FREQUENCY);
312
    //execute:
313
    ivel->velocityMove(id, speed);
314
    //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);
315

    
316
    target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value();
317
}
318

    
319
//! actually execute the scheduled motion commands
320
void iCubJointInterface::execute_motion(){
321

    
322
    // set up neck and eye motion commands:
323
    if (POSITION_CONTROL){
324
        //position control
325
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
326
            set_target_in_positionmode(i, target_angle[i]);
327
        }
328
    }else{
329
        //velocity control
330
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
331
            set_target_in_velocitymode(i, target_angle[i]);
332
        }
333
    }
334
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
335

    
336

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

    
340
    //eyebrows are set using a special command as well:
341
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
342
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
343

    
344
    //mouth
345
    set_mouth();
346

    
347

    
348
}
349

    
350
void iCubJointInterface::set_mouth(){
351
    //convert from 6DOF mouth displacement to icub leds:
352
    int led_value = 0;
353

    
354
    //fetch center opening:
355
    double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
356
    bool mouth_open = (center_opening>15.0)?true:false;
357

    
358
    //side of mouth high or low?
359
    double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0;
360
    double left_avg   = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0;
361
    double right_avg  = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0;
362

    
363
    //happy, neutral or sad?
364
    double diff_l = center_avg - left_avg;
365
    double diff_r = center_avg - right_avg;
366
    double diff   = (diff_l+diff_r)/2.0;
367

    
368
    if (diff > 2.0){
369
        if (mouth_open){
370
            led_value = 0x14;
371
        }else{
372
            if (diff > 2.6){
373
                led_value = 0x0A;
374
            }else{
375
                led_value = 0x0B;
376
            }
377
        }
378
    }else if (diff < -3.0){
379
        if (mouth_open){
380
            led_value = 0x06;
381
        }else{
382
            led_value = 0x18;
383
        }
384
    }else if (diff < -2.0){
385
        if (mouth_open){
386
            led_value = 0x04; //0x25;
387
        }else{
388
            led_value = 0x08;
389
        }
390
    }else{
391
        if (mouth_open){
392
            led_value = 0x16;
393
        }else{
394
            led_value = 0x08;
395
        }
396
    }
397

    
398

    
399
    if (led_value == previous_mouth_state){
400
        //no update necessary
401
        return;
402
    }
403

    
404
    previous_mouth_state = led_value;
405

    
406
    //convert to string:
407
    char buf[10];
408
    sprintf(buf, "M%02X",led_value);
409

    
410
    /*printf("> sending mouth '%s'\n",buf);
411
    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]);
412
    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]);
413
    printf("  mouth  open=%3.2f diff=%3.2f\n", center_opening, diff);*/
414

    
415
    //add mouth:
416
    Bottle &cmd = emotion_port[3].prepare();
417
    cmd.clear();
418
    cmd.addString(buf);
419
    emotion_port[3].write();
420

    
421

    
422
    //store joint values which we do not handle on icub here:
423
    double timestamp = get_timestamp_ms();
424
    JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER,   target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp);
425
    JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER,   target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp);
426
    JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp);
427
    JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp);
428
    JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER,  target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp);
429
    JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER,  target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp);
430

    
431
}
432

    
433
double iCubJointInterface::get_timestamp_ms(){
434
    struct timespec spec;
435
    clock_gettime(CLOCK_REALTIME, &spec);
436
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
437
}
438

    
439
//! set the current position of a joint
440
//! \param id of joint
441
//! \param float value of position
442
//! \param double timestamp
443
void iCubJointInterface::fetch_position(int id, double value, double timestamp){
444
    //store joint based on id:
445
    switch(id){
446
        default:
447
            printf("> ERROR: unhandled joint id %d\n",id);
448
            return;
449

    
450
        case(100):
451
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp);
452
            break;
453

    
454
        case(2):
455
            //PAN is inverted!
456
            JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp);
457
            break;
458

    
459
        case(0):
460
            JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp);
461
            break;
462

    
463
        case(1):
464
            JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp);
465
            break;
466

    
467
        case(3):
468
            JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp);
469
            break;
470

    
471
        //icub handles eyes differently, we have to set pan angle + vergence
472
        case(4): {//pan
473
            last_pos_eye_pan = value;
474
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
475
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
476

    
477
            //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);
478
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
479
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
480
            break;
481
        }
482

    
483
        case(5): { //vergence
484
            last_pos_eye_vergence = value;
485
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
486
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
487

    
488
            //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);
489
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
490
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
491
            break;
492
        }
493
    }
494

    
495

    
496
}
497

    
498
//! set the current speed of a joint
499
//! \param enum id of joint
500
//! \param float value of speed
501
//! \param double timestamp
502
void iCubJointInterface::fetch_speed(int id, double value, double timestamp){
503

    
504
    switch(id){
505
        default:
506
            printf("> ERROR: unhandled joint id %d\n",id);
507
            return;
508

    
509
        case(2):
510
            JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp);
511
            break;
512

    
513
        case(0):
514
            JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp);
515
            break;
516

    
517
        case(1):
518
            JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp);
519
            break;
520

    
521
        case(3):
522
            JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp);
523
            break;
524

    
525
        //icub handles eyes differently, we have to set pan angle + vergence
526
        case(4): {//pan
527
            last_vel_eye_pan = value;
528
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
529
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
530

    
531
            //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);
532
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
533
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
534
            break;
535
        }
536

    
537
        case(5): { //vergence
538
            last_vel_eye_pan = value;
539
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
540
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
541

    
542
            //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);
543
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
544
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
545
            break;
546
        }
547
    }
548
/*
549
    JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
550
    JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
551
    JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
552
    JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
553
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
554
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
555

556
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_LOWER, 0.0, timestamp);
557
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_UPPER, 0.0, timestamp);
558
    JointInterface::store_incoming_speed(ID_EYES_LEFT_BROW, 0.0, timestamp);
559

560
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_LOWER, 0.0, timestamp);
561
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_UPPER,0.0, timestamp);
562
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_BROW, 0.0, timestamp);*/
563
    /*
564
    //fetch enum id:
565
    int e = convert_motorid_to_enum(device->get_device_id());
566
    if (e == -1){
567
        return; //we are not interested in that data, so we just return here
568
    }
569

570
    JointInterface::store_incoming_speed(e, device->get_register(XSC3_REGISTER_MOTORSPEED), timestamp);*/
571

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

584
    return it->second;
585
}
586

587

588
//! conversion table for our ids to humotion motor ids:
589
//! \param  int value of motor id
590
//! \return enum from JointInterface::JOINT_ID_ENUM
591
int HumotionJointInterface::convert_motorid_to_enum(int id){
592
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
593
    if(it == enum_id_bimap.left.end()) {
594
        //key does not exists, we are not interested in that dataset, return -1
595
        return -1;
596
    }
597

598
    return it->second;
599
}
600
*/
601

    
602
//! prepare and enable a joint
603
//! NOTE: this should also prefill the min/max positions for this joint
604
//! \param the enum id of a joint
605
void iCubJointInterface::enable_joint(int e){
606
    //FIXME ADD THIS:
607
    // enable the amplifier and the pid controller on each joint
608
    /*for (i = 0; i < nj; i++) {
609
       amp->enableAmp(i);
610
       pid->enablePid(i);
611
    }*/
612

    
613

    
614
    //set up smooth motion controller
615
    //step1: set up framerate
616
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
617

    
618
    //step2: set controllertype:
619
    //printf("> activating smooth motion control for joint id 0x%02X (%s)\n", motor_id, joint_name.c_str());
620
    //dev->set_register_blocking(XSC3_REGISTER_PID_CONTROLLER, XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK, true);
621

    
622
    //step3: set pid controller:
623
    /*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)){
624
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
625
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
626
    }*/
627

    
628
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
629

    
630
    //check if setting pid controllertype was successfull:
631
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
632
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
633
        exit(1);
634
    }*/
635

    
636
    //fetch min/max:
637
   // init_joint(e);
638

    
639
    //ok fine, now enable motor:
640
    //printf("> enabling motor %s\n", joint_name.c_str());
641
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
642

    
643
}
644

    
645
void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){
646
    double min, max;
647
    ilimits->getLimits(id, &min, &max);
648
    joint_min[e] = min;
649
    joint_max[e] = max;
650
}
651

    
652
//! initialise a joint (set up controller mode etc)
653
//! \param joint enum
654
void iCubJointInterface::init_joints(){
655
    store_min_max(ilimits, 0, ID_NECK_TILT);
656
    store_min_max(ilimits, 1, ID_NECK_ROLL);
657
    store_min_max(ilimits, 2, ID_NECK_PAN);
658
    store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
659

    
660
    //icub handles eyes differently, we have to set pan angle + vergence
661
    double pan_min, pan_max, vergence_min, vergence_max;
662
    ilimits->getLimits(4, &pan_min, &pan_max);
663
    ilimits->getLimits(5, &vergence_min, &vergence_max);
664

    
665
    //this is not 100% correct, should be fixed:
666
    joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
667
    joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
668
    joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR];
669
    joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR];
670

    
671
    //eyelids:
672
    joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30;
673
    joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30;
674
    lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
675

    
676
    //eyebrows:
677
    joint_min[ID_EYES_LEFT_BROW] = -50;
678
    joint_max[ID_EYES_LEFT_BROW] = 50;
679
    joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW];
680
    joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW];
681

    
682
    //mouth:
683
    joint_min[ID_LIP_CENTER_UPPER] = 5;
684
    joint_max[ID_LIP_CENTER_UPPER] = 50;
685
    joint_min[ID_LIP_CENTER_LOWER] = 5;
686
    joint_max[ID_LIP_CENTER_LOWER] = 50;
687
    joint_min[ID_LIP_LEFT_UPPER] = 5;
688
    joint_max[ID_LIP_LEFT_UPPER] = 50;
689
    joint_min[ID_LIP_LEFT_LOWER] = 5;
690
    joint_max[ID_LIP_LEFT_LOWER] = 50;
691
    joint_min[ID_LIP_RIGHT_UPPER] = 5;
692
    joint_max[ID_LIP_RIGHT_UPPER] = 50;
693
    joint_min[ID_LIP_RIGHT_LOWER] = 5;
694
    joint_max[ID_LIP_RIGHT_LOWER] = 50;
695

    
696

    
697
}
698

    
699
//! shutdown and disable a joint
700
//! \param the enum id of a joint
701
void iCubJointInterface::disable_joint(int e){
702
    /*
703
        //first: convert humotion enum to our enum:
704
        int motor_id = convert_enum_to_motorid(e);
705
        if (motor_id == -1){
706
            return; //we are not interested in that data, so we just return here
707
        }
708

709
        //fetch device:
710
        Device *dev = get_device(motor_id);
711
        printf("> FIXME: ADD DISABLE CODE\n");
712
        printf("> FIXME: ADD DISABLE CODE\n");
713
        printf("> FIXME: ADD DISABLE CODE\n");
714
        printf("> FIXME: ADD DISABLE CODE\n");
715
        printf("> FIXME: ADD DISABLE CODE\n");
716
        printf("> FIXME: ADD DISABLE CODE\n");
717
        printf("> FIXME: ADD DISABLE CODE\n");
718
        printf("> FIXME: ADD DISABLE CODE\n");
719
        printf("> FIXME: ADD DISABLE CODE\n");
720
        */
721
}