Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / src / mekajointinterface.cpp @ 473a6a6c

History | View | Annotate | Download (30.354 KB)

1
#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
void MekaJointInterface::incoming_jointstates(const sensor_msgs::JointState & msg){
8
    //joint_pos_global = msg.position[3];
9
    cout << msg;
10
}
11

    
12
//! constructor
13
MekaJointInterface::MekaJointInterface(string _scope) : humotion::server::JointInterface(){
14
    scope = _scope;
15

    
16
    //subscribe to meka joint states
17
    ros::NodeHandle n;
18
    joint_state_subscriber = n.subscribe(scope + "joint_states", 150, &MekaJointInterface::incoming_jointstates , this);
19

    
20

    
21
    //add mapping from ids to enums:
22
    //this might look strange at the first sight but we need to have a generic
23
    //way to acces joints from libhumotion. therefore the lib uses its enum with ID_* enum ids
24
    //to access the joints. now we need to define a mapping to map those to our motor ids.
25
    //this is what we use the enum bimap for (convertion fro/to motorid is handled
26
    //by \sa convert_enum_to_motorid() and \sa convert_motorid_to_enum() lateron
27
/*
28
    //MOUTH
29
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_UPPER,   ID_LIP_LEFT_UPPER));
30
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_LOWER,   ID_LIP_LEFT_LOWER));
31
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_UPPER, ID_LIP_CENTER_UPPER));
32
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_LOWER, ID_LIP_CENTER_LOWER));
33
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_UPPER,  ID_LIP_RIGHT_UPPER));
34
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_LOWER,  ID_LIP_RIGHT_LOWER));
35

36
    //NECK
37
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_PAN,    ID_NECK_PAN));
38
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_TILT,   ID_NECK_TILT));
39
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_ROLL,   ID_NECK_ROLL));
40

41
    //EYES
42
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LR,   ID_EYES_LEFT_LR));
43
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LR,   ID_EYES_RIGHT_LR));
44
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_BOTH_UD,   ID_EYES_BOTH_UD));
45

46
    //EYELIDS
47
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_LOWER, ID_EYES_LEFT_LID_LOWER));
48
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_UPPER, ID_EYES_LEFT_LID_UPPER));
49
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_BROW, ID_EYES_LEFT_BROW));
50

51
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_LOWER, ID_EYES_RIGHT_LID_LOWER));
52
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_UPPER,ID_EYES_RIGHT_LID_UPPER));
53
    enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_BROW, ID_EYES_RIGHT_BROW));
54

55
    Property options;
56
    options.put("device", "remote_controlboard");
57
    options.put("local", "/local/head");
58
    options.put("remote", scope+"/head");
59
    dd.open(options);
60

61
    //fetch views:
62
    dd.view(iencs);
63
    dd.view(ipos);
64
    dd.view(ivel);
65
    dd.view(ilimits);
66

67
    if ( (!iencs) || (!ipos) || (!ilimits) || (!ivel)){
68
        printf("> ERROR: failed to open icub views\n");
69
        exit(EXIT_FAILURE);
70
    }
71

72
    int joints;
73

74
    //tell humotion about min/max joint values:
75
    init_joints();
76

77
    iencs->getAxes(&joints);
78
    positions.resize(joints);
79
    velocities.resize(joints);
80
    commands.resize(joints);
81

82
    //set position mode:
83
    if (POSITION_CONTROL){
84
        commands=200000.0;
85
        ipos->setRefAccelerations(commands.data());
86
        ipos->setPositionMode();
87
    }else{
88
        ivel->setVelocityMode();
89
        commands=1000000;
90
        ivel->setRefAccelerations(commands.data());
91
    }
92

93
    //attach to facial expressions:
94
    string emotion_scope = scope + "/face/raw/in";
95
    printf("> opening connection to %s\n", emotion_scope.c_str());
96

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

    
112
//! destructor
113
MekaJointInterface::~MekaJointInterface(){
114
}
115

    
116

    
117

    
118
void MekaJointInterface::run(){
119
   //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
120
   //data_receiver->start();
121
}
122

    
123

    
124
//! set the target position of a joint
125
//! \param enum id of joint
126
//! \param float value
127
void MekaJointInterface::publish_target_position(int e){
128
    #if 0
129
    //first: convert humotion enum to our enum:
130
    int id = convert_enum_to_motorid(e);
131
    if (id == -1){
132
        return; //we are not interested in that data, so we just return here
133
    }
134

135
    if (id == ICUB_ID_NECK_PAN){
136
        //PAN seems to be swapped
137
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
138
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
139
        //icub handles eyes differently, we have to set pan angle + vergence
140
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
141
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
142
        //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);
143

144
        store_joint(ICUB_ID_EYES_PAN, pan);
145
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
146
    }else{
147
        store_joint(id, joint_target[e]);
148
    }
149
    #endif
150
}
151

152

153
//! actually execute the scheduled motion commands
154
void MekaJointInterface::execute_motion(){
155
    #if 0
156
    // set up neck and eye motion commands:
157
    if (POSITION_CONTROL){
158
        //position control
159
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
160
            set_target_in_positionmode(i, target_angle[i]);
161
        }
162
    }else{
163
        //velocity control
164
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
165
            set_target_in_velocitymode(i, target_angle[i]);
166
        }
167
    }
168
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
169

170

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

174
    //eyebrows are set using a special command as well:
175
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
176
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
177

178
    //mouth
179
    set_mouth();
180

181
    #endif
182
}
183

184

185
//! prepare and enable a joint
186
//! NOTE: this should also prefill the min/max positions for this joint
187
//! \param the enum id of a joint
188
void MekaJointInterface::enable_joint(int e){
189
#if 0
190
    //FIXME ADD THIS:
191
    // enable the amplifier and the pid controller on each joint
192
    /*for (i = 0; i < nj; i++) {
193
       amp->enableAmp(i);
194
       pid->enablePid(i);
195
    }*/
196

197

198
    //set up smooth motion controller
199
    //step1: set up framerate
200
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
201

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

206
    //step3: set pid controller:
207
    /*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)){
208
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
209
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
210
    }*/
211

212
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
213

214
    //check if setting pid controllertype was successfull:
215
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
216
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
217
        exit(1);
218
    }*/
219

220
    //fetch min/max:
221
   // init_joint(e);
222

223
    //ok fine, now enable motor:
224
    //printf("> enabling motor %s\n", joint_name.c_str());
225
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
226
#endif
227
}
228

    
229
//! shutdown and disable a joint
230
//! \param the enum id of a joint
231
void MekaJointInterface::disable_joint(int e){
232
    /*
233
        //first: convert humotion enum to our enum:
234
        int motor_id = convert_enum_to_motorid(e);
235
        if (motor_id == -1){
236
            return; //we are not interested in that data, so we just return here
237
        }
238

239
        //fetch device:
240
        Device *dev = get_device(motor_id);
241
        printf("> FIXME: ADD DISABLE CODE\n");
242
        printf("> FIXME: ADD DISABLE CODE\n");
243
        printf("> FIXME: ADD DISABLE CODE\n");
244
        printf("> FIXME: ADD DISABLE CODE\n");
245
        printf("> FIXME: ADD DISABLE CODE\n");
246
        printf("> FIXME: ADD DISABLE CODE\n");
247
        printf("> FIXME: ADD DISABLE CODE\n");
248
        printf("> FIXME: ADD DISABLE CODE\n");
249
        printf("> FIXME: ADD DISABLE CODE\n");
250
        */
251
}
252

    
253
#if 0
254

255
//! conversion table for humotion motor ids to our ids:
256
//! \param enum from JointInterface::JOINT_ID_ENUM
257
//! \return int value of motor id
258
int iCubJointInterface::convert_enum_to_motorid(int e){
259
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
260
    if(it == enum_id_bimap.right.end()) {
261
        //key does not exists, we are not interested in that dataset, return -1
262
        return -1;
263
    }
264
    return it->second;
265
}
266

267

268
//! conversion table for our ids to humotion motor ids:
269
//! \param  int value of motor id
270
//! \return enum from JointInterface::JOINT_ID_ENUM
271
int iCubJointInterface::convert_motorid_to_enum(int id){
272
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
273
    if(it == enum_id_bimap.left.end()) {
274
        //key does not exists, we are not interested in that dataset, return -1
275
        return -1;
276
    }
277
    return it->second;
278
}
279

280
//! special command to set eyelid angle
281
//! \param angle in degrees
282
void iCubJointInterface::set_eyelid_angle(double angle){
283
    if (emotion_port[0].getOutputCount()>0){
284
        //try to set the value based on the upper one
285
        //some guesses from the sim: S30 = 0° / S40 = 10°
286
        int opening = (25.0 + 0.8*angle);
287
        opening = min(48, max(24, opening));
288

289
        if (opening == lid_opening_previous){
290
            //no update necessary
291
            return;
292
        }
293

294
        lid_angle = angle;
295
        lid_opening_previous = opening;
296

297
        char buf[20];
298
        sprintf(buf, "S%2d", opening);
299

300
        //printf("> SETTING EYELID '%s' (%f -> %d)\n",buf,angle,opening);
301
        Bottle &cmd = emotion_port[0].prepare();
302
        cmd.clear();
303
        cmd.addString(buf);
304
        emotion_port[0].write();
305
    }else{
306
        printf("> ERROR: no icub emotion output\n");
307
        exit(EXIT_FAILURE);
308
    }
309
}
310

311
//! special command to set the eyebrow angle
312
//! \param id {0=left, 1=right)
313
//! \param angle in degrees
314
void iCubJointInterface::set_eyebrow_angle(int id){
315
    int port_id;
316
    if (id == ICUB_ID_EYES_LEFT_BROW){
317
        port_id = 1;
318
    }else{
319
        port_id = 2;
320
    }
321

322
    if (emotion_port[port_id].getOutputCount()>0){
323
        double angle = target_angle[id];
324
        int icub_val = 0;
325

326
        //swap rotation direction:
327
        if (id==ICUB_ID_EYES_LEFT_BROW) angle = -angle;
328

329
        //convert to icub representation
330
        if (angle < -20){
331
            icub_val = 1;
332
        }else if (angle<10){
333
            icub_val = 2;
334
        }else if (angle<20){
335
            icub_val = 4;
336
        }else{
337
            icub_val = 8;
338
        }
339

340
        //make sure to update only on new values:
341
        if (icub_val == target_angle_previous[id]){
342
                //no updata necessary
343
                return;
344
        }
345

346
        //store actual value:
347
        target_angle_previous[id] = icub_val;
348

349

350
        string cmd_s;
351
        if (id==ICUB_ID_EYES_LEFT_BROW){
352
            cmd_s = "L0" + to_string(icub_val);
353
        }else{
354
            cmd_s = "R0" + to_string(icub_val);
355
        }
356

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

359
        Bottle &cmd = emotion_port[port_id].prepare();
360
        cmd.clear();
361
        cmd.addString(cmd_s);
362
        emotion_port[port_id].write();
363
    }else{
364
        printf("> ERROR: no icub emotion output\n");
365
        exit(EXIT_FAILURE);
366
    }
367
}
368

369
void iCubJointInterface::run(){
370
    iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
371
    data_receiver->start();
372
}
373

374
//! set the target position of a joint
375
//! \param enum id of joint
376
//! \param float value
377
void iCubJointInterface::publish_target_position(int e){
378
    //first: convert humotion enum to our enum:
379
    int id = convert_enum_to_motorid(e);
380
    if (id == -1){
381
        return; //we are not interested in that data, so we just return here
382
    }
383

384
    if (id == ICUB_ID_NECK_PAN){
385
        //PAN seems to be swapped
386
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
387
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
388
        //icub handles eyes differently, we have to set pan angle + vergence
389
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
390
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
391
        //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);
392

393
        store_joint(ICUB_ID_EYES_PAN, pan);
394
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
395
    }else{
396
        store_joint(id, joint_target[e]);
397
    }
398
}
399

400

401
//! set the target position of a joint
402
//! \param id of joint
403
//! \param float value of position
404
void iCubJointInterface::store_joint(int id, float value){
405
    //printf("> set joint %d = %f\n",id,value);
406
    target_angle[id] = value;
407
    //ipos->positionMove(id, value);
408
}
409

410
//! execute a move in position mode
411
//! \param id of joint
412
//! \param angle
413
void iCubJointInterface::set_target_in_positionmode(int id, double value){
414
    if (id>ICUB_ID_EYES_VERGENCE){
415
        printf("> ERROR: set_target_positionmode(id=%d, %3.2f) not supported for this id\n",id,value);
416
        return;
417
    }
418
#if 0
419
    //set speed cacluated as in velocity + set position -> replicates smoothmotion from flobi?!
420

421
    //first: calculate necessary speed to reach the given target within the next clock tick:
422
    double distance = value - target_angle_previous[id];
423
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
424
    //calculate speed for that:
425
    double speed = 0.85 * distance * ((double)MAIN_LOOP_FREQUENCY);
426

427
    //set up speed for controller:
428
    ipos->setRefSpeed(id, speed);
429
#endif
430
    //execute motion
431
    ipos->positionMove(id, value);
432
}
433

    
434
//! execute a move in velocity mode
435
//! \param id of joint
436
//! \param angle
437
void iCubJointInterface::set_target_in_velocitymode(int id, double value){
438
    //first: calculate necessary speed to reach the given target within the next clock tick:
439
    double distance = value - target_angle_previous[id];
440
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
441
    distance = 0.85 * distance;
442
    //calculate speed
443
    double speed = distance * ((double)MAIN_LOOP_FREQUENCY);
444
    //execute:
445
    ivel->velocityMove(id, speed);
446
    //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);
447

    
448
    target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value();
449
}
450

    
451
//! actually execute the scheduled motion commands
452
void iCubJointInterface::execute_motion(){
453

    
454
    // set up neck and eye motion commands:
455
    if (POSITION_CONTROL){
456
        //position control
457
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
458
            set_target_in_positionmode(i, target_angle[i]);
459
        }
460
    }else{
461
        //velocity control
462
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
463
            set_target_in_velocitymode(i, target_angle[i]);
464
        }
465
    }
466
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
467

    
468

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

    
472
    //eyebrows are set using a special command as well:
473
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
474
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
475

    
476
    //mouth
477
    set_mouth();
478

    
479

    
480
}
481

    
482
void iCubJointInterface::set_mouth(){
483
    //convert from 6DOF mouth displacement to icub leds:
484
    int led_value = 0;
485

    
486
    //fetch center opening:
487
    double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
488
    bool mouth_open = (center_opening>15.0)?true:false;
489

    
490
    //side of mouth high or low?
491
    double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0;
492
    double left_avg   = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0;
493
    double right_avg  = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0;
494

    
495
    //happy, neutral or sad?
496
    double diff_l = center_avg - left_avg;
497
    double diff_r = center_avg - right_avg;
498
    double diff   = (diff_l+diff_r)/2.0;
499

    
500
    if (diff > 2.0){
501
        if (mouth_open){
502
            led_value = 0x14;
503
        }else{
504
            if (diff > 2.6){
505
                led_value = 0x0A;
506
            }else{
507
                led_value = 0x0B;
508
            }
509
        }
510
    }else if (diff < -3.0){
511
        if (mouth_open){
512
            led_value = 0x06;
513
        }else{
514
            led_value = 0x18;
515
        }
516
    }else if (diff < -2.0){
517
        if (mouth_open){
518
            led_value = 0x04; //0x25;
519
        }else{
520
            led_value = 0x08;
521
        }
522
    }else{
523
        if (mouth_open){
524
            led_value = 0x16;
525
        }else{
526
            led_value = 0x08;
527
        }
528
    }
529

    
530

    
531
    if (led_value == previous_mouth_state){
532
        //no update necessary
533
        return;
534
    }
535

    
536
    previous_mouth_state = led_value;
537

    
538
    //convert to string:
539
    char buf[10];
540
    sprintf(buf, "M%02X",led_value);
541

    
542
    /*printf("> sending mouth '%s'\n",buf);
543
    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]);
544
    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]);
545
    printf("  mouth  open=%3.2f diff=%3.2f\n", center_opening, diff);*/
546

    
547
    //add mouth:
548
    Bottle &cmd = emotion_port[3].prepare();
549
    cmd.clear();
550
    cmd.addString(buf);
551
    emotion_port[3].write();
552

    
553

    
554
    //store joint values which we do not handle on icub here:
555
    double timestamp = get_timestamp_ms();
556
    JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER,   target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp);
557
    JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER,   target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp);
558
    JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp);
559
    JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp);
560
    JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER,  target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp);
561
    JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER,  target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp);
562

    
563
}
564

    
565
double iCubJointInterface::get_timestamp_ms(){
566
    struct timespec spec;
567
    clock_gettime(CLOCK_REALTIME, &spec);
568
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
569
}
570

    
571
//! set the current position of a joint
572
//! \param id of joint
573
//! \param float value of position
574
//! \param double timestamp
575
void iCubJointInterface::fetch_position(int id, double value, double timestamp){
576
    //store joint based on id:
577
    switch(id){
578
        default:
579
            printf("> ERROR: unhandled joint id %d\n",id);
580
            return;
581

    
582
        case(100):
583
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp);
584
            break;
585

    
586
        case(2):
587
            //PAN is inverted!
588
            JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp);
589
            break;
590

    
591
        case(0):
592
            JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp);
593
            break;
594

    
595
        case(1):
596
            JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp);
597
            break;
598

    
599
        case(3):
600
            JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp);
601
            break;
602

    
603
        //icub handles eyes differently, we have to set pan angle + vergence
604
        case(4): {//pan
605
            last_pos_eye_pan = value;
606
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
607
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
608

    
609
            //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);
610
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
611
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
612
            break;
613
        }
614

    
615
        case(5): { //vergence
616
            last_pos_eye_vergence = value;
617
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
618
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
619

    
620
            //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);
621
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
622
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
623
            break;
624
        }
625
    }
626

    
627

    
628
}
629

    
630
//! set the current speed of a joint
631
//! \param enum id of joint
632
//! \param float value of speed
633
//! \param double timestamp
634
void iCubJointInterface::fetch_speed(int id, double value, double timestamp){
635

    
636
    switch(id){
637
        default:
638
            printf("> ERROR: unhandled joint id %d\n",id);
639
            return;
640

    
641
        case(2):
642
            JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp);
643
            break;
644

    
645
        case(0):
646
            JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp);
647
            break;
648

    
649
        case(1):
650
            JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp);
651
            break;
652

    
653
        case(3):
654
            JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp);
655
            break;
656

    
657
        //icub handles eyes differently, we have to set pan angle + vergence
658
        case(4): {//pan
659
            last_vel_eye_pan = value;
660
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
661
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
662

    
663
            //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);
664
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
665
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
666
            break;
667
        }
668

    
669
        case(5): { //vergence
670
            last_vel_eye_pan = value;
671
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
672
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
673

    
674
            //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);
675
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
676
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
677
            break;
678
        }
679
    }
680
/*
681
    JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
682
    JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
683
    JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
684
    JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
685
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
686
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
687

688
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_LOWER, 0.0, timestamp);
689
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_UPPER, 0.0, timestamp);
690
    JointInterface::store_incoming_speed(ID_EYES_LEFT_BROW, 0.0, timestamp);
691

692
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_LOWER, 0.0, timestamp);
693
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_UPPER,0.0, timestamp);
694
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_BROW, 0.0, timestamp);*/
695
    /*
696
    //fetch enum id:
697
    int e = convert_motorid_to_enum(device->get_device_id());
698
    if (e == -1){
699
        return; //we are not interested in that data, so we just return here
700
    }
701

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

    
704
}
705
/*
706
//! conversion table for humotion motor ids to our ids:
707
//! \param enum from JointInterface::JOINT_ID_ENUM
708
//! \return int value of motor id
709
int HumotionJointInterface::convert_enum_to_motorid(int e){
710
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
711
    if(it == enum_id_bimap.right.end()) {
712
        //key does not exists, we are not interested in that dataset, return -1
713
        return -1;
714
    }
715

716
    return it->second;
717
}
718

719

720
//! conversion table for our ids to humotion motor ids:
721
//! \param  int value of motor id
722
//! \return enum from JointInterface::JOINT_ID_ENUM
723
int HumotionJointInterface::convert_motorid_to_enum(int id){
724
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
725
    if(it == enum_id_bimap.left.end()) {
726
        //key does not exists, we are not interested in that dataset, return -1
727
        return -1;
728
    }
729

730
    return it->second;
731
}
732
*/
733

    
734
//! prepare and enable a joint
735
//! NOTE: this should also prefill the min/max positions for this joint
736
//! \param the enum id of a joint
737
void iCubJointInterface::enable_joint(int e){
738
    //FIXME ADD THIS:
739
    // enable the amplifier and the pid controller on each joint
740
    /*for (i = 0; i < nj; i++) {
741
       amp->enableAmp(i);
742
       pid->enablePid(i);
743
    }*/
744

    
745

    
746
    //set up smooth motion controller
747
    //step1: set up framerate
748
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
749

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

    
754
    //step3: set pid controller:
755
    /*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)){
756
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
757
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
758
    }*/
759

    
760
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
761

    
762
    //check if setting pid controllertype was successfull:
763
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
764
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
765
        exit(1);
766
    }*/
767

    
768
    //fetch min/max:
769
   // init_joint(e);
770

    
771
    //ok fine, now enable motor:
772
    //printf("> enabling motor %s\n", joint_name.c_str());
773
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
774

    
775
}
776

    
777
void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){
778
    double min, max;
779
    ilimits->getLimits(id, &min, &max);
780
    joint_min[e] = min;
781
    joint_max[e] = max;
782
}
783

    
784
//! initialise a joint (set up controller mode etc)
785
//! \param joint enum
786
void iCubJointInterface::init_joints(){
787
    store_min_max(ilimits, 0, ID_NECK_TILT);
788
    store_min_max(ilimits, 1, ID_NECK_ROLL);
789
    store_min_max(ilimits, 2, ID_NECK_PAN);
790
    store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
791

    
792
    //icub handles eyes differently, we have to set pan angle + vergence
793
    double pan_min, pan_max, vergence_min, vergence_max;
794
    ilimits->getLimits(4, &pan_min, &pan_max);
795
    ilimits->getLimits(5, &vergence_min, &vergence_max);
796

    
797
    //this is not 100% correct, should be fixed:
798
    joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
799
    joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
800
    joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR];
801
    joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR];
802

    
803
    //eyelids:
804
    joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30;
805
    joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30;
806
    lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
807

    
808
    //eyebrows:
809
    joint_min[ID_EYES_LEFT_BROW] = -50;
810
    joint_max[ID_EYES_LEFT_BROW] = 50;
811
    joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW];
812
    joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW];
813

    
814
    //mouth:
815
    joint_min[ID_LIP_CENTER_UPPER] = 5;
816
    joint_max[ID_LIP_CENTER_UPPER] = 50;
817
    joint_min[ID_LIP_CENTER_LOWER] = 5;
818
    joint_max[ID_LIP_CENTER_LOWER] = 50;
819
    joint_min[ID_LIP_LEFT_UPPER] = 5;
820
    joint_max[ID_LIP_LEFT_UPPER] = 50;
821
    joint_min[ID_LIP_LEFT_LOWER] = 5;
822
    joint_max[ID_LIP_LEFT_LOWER] = 50;
823
    joint_min[ID_LIP_RIGHT_UPPER] = 5;
824
    joint_max[ID_LIP_RIGHT_UPPER] = 50;
825
    joint_min[ID_LIP_RIGHT_LOWER] = 5;
826
    joint_max[ID_LIP_RIGHT_LOWER] = 50;
827

    
828

    
829
}
830

    
831
//! shutdown and disable a joint
832
//! \param the enum id of a joint
833
void iCubJointInterface::disable_joint(int e){
834
    /*
835
        //first: convert humotion enum to our enum:
836
        int motor_id = convert_enum_to_motorid(e);
837
        if (motor_id == -1){
838
            return; //we are not interested in that data, so we just return here
839
        }
840

841
        //fetch device:
842
        Device *dev = get_device(motor_id);
843
        printf("> FIXME: ADD DISABLE CODE\n");
844
        printf("> FIXME: ADD DISABLE CODE\n");
845
        printf("> FIXME: ADD DISABLE CODE\n");
846
        printf("> FIXME: ADD DISABLE CODE\n");
847
        printf("> FIXME: ADD DISABLE CODE\n");
848
        printf("> FIXME: ADD DISABLE CODE\n");
849
        printf("> FIXME: ADD DISABLE CODE\n");
850
        printf("> FIXME: ADD DISABLE CODE\n");
851
        printf("> FIXME: ADD DISABLE CODE\n");
852
        */
853
}
854
#endif