Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / src / mekajointinterface.cpp @ e8e20dfe

History | View | Annotate | Download (30.887 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
    //fetch current timestamp
9
    double timestamp = get_timestamp_ms();
10

    
11
    //iterate through incoming joints and filter out joints we need:
12
    for(int i=0; i<msg.name.size(); i++){
13
        string name = msg.name[i];
14
        //printf("incoming data for joint '%s'\n", name.c_str());
15

    
16
        int id = -1;
17
        if (name == "head_j1"){
18
            id = ID_NECK_PAN;
19
        }else if(name == "head_j0"){
20
            id = ID_NECK_TILT;
21
        }
22

    
23
        //store data:
24
        if (id != -1){
25
            //printf("> storing joint data for joint id %d\n", id);
26
            JointInterface::store_incoming_position(id, msg.position[i], timestamp);
27
            JointInterface::store_incoming_speed(   id, msg.velocity[i], timestamp);
28
        }
29
    }
30

    
31
    //store dummy positions for joints we do not know about:
32
    store_dummy_data(ID_LIP_LEFT_UPPER, timestamp);
33
    store_dummy_data(ID_LIP_LEFT_LOWER, timestamp);
34
    store_dummy_data(ID_LIP_CENTER_UPPER, timestamp);
35
    store_dummy_data(ID_LIP_CENTER_LOWER, timestamp);
36
    store_dummy_data(ID_LIP_RIGHT_UPPER, timestamp);
37
    store_dummy_data(ID_LIP_RIGHT_LOWER, timestamp);
38

    
39
    store_dummy_data(ID_NECK_ROLL, timestamp);
40
    store_dummy_data(ID_EYES_BOTH_UD, timestamp);
41
    store_dummy_data(ID_EYES_LEFT_LR, timestamp);
42
    store_dummy_data(ID_EYES_RIGHT_LR, timestamp);
43
    store_dummy_data(ID_EYES_LEFT_LID_LOWER, timestamp);
44
    store_dummy_data(ID_EYES_LEFT_LID_UPPER, timestamp);
45
    store_dummy_data(ID_EYES_LEFT_BROW, timestamp);
46
    store_dummy_data(ID_EYES_RIGHT_LID_LOWER, timestamp);
47
    store_dummy_data(ID_EYES_RIGHT_LID_UPPER, timestamp);
48
    store_dummy_data(ID_EYES_RIGHT_BROW, timestamp);
49

    
50
}
51

    
52
void MekaJointInterface::store_dummy_data(int id, double timestamp){
53
    JointInterface::store_incoming_position(id, 0.0, timestamp);
54
    JointInterface::store_incoming_speed(id, 0.0, timestamp);
55
}
56

    
57
//! constructor
58
MekaJointInterface::MekaJointInterface(string _scope) : humotion::server::JointInterface(){
59
    scope = _scope;
60
    string js_topic = scope + "joint_states";
61
    string target_topic = scope + "meka_roscontrol/head_position_trajectory_controller/command";
62

    
63
    //subscribe to meka joint states
64
    int argc = 0;
65
    ros::init(argc, (char**)NULL, "meka_humotion");
66
    ros::NodeHandle n;
67

    
68

    
69
    printf("> listening on jointstates on '%s'\n",js_topic.c_str());
70
    joint_state_subscriber = n.subscribe(js_topic, 150, &MekaJointInterface::incoming_jointstates , this);
71

    
72
    printf("> sending targets on '%s'\n", target_topic.c_str());
73
    target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(target_topic, 100);
74

    
75

    
76
    //tell humotion about min/max joint values:
77
    init_joints();
78
}
79

    
80
//! destructor
81
MekaJointInterface::~MekaJointInterface(){
82
}
83

    
84

    
85

    
86
void MekaJointInterface::run(){
87
   //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
88
   //data_receiver->start();
89
   ros::spin();
90
}
91

    
92

    
93
double MekaJointInterface::get_timestamp_ms(){
94
    struct timespec spec;
95
    clock_gettime(CLOCK_REALTIME, &spec);
96
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
97
}
98

    
99
//! set the target position of a joint
100
//! \param enum id of joint
101
//! \param float value
102
void MekaJointInterface::publish_target_position(int e){
103
    #if 0
104
    //first: convert humotion enum to our enum:
105
    int id = convert_enum_to_motorid(e);
106
    if (id == -1){
107
        return; //we are not interested in that data, so we just return here
108
    }
109

110
    if (id == ICUB_ID_NECK_PAN){
111
        //PAN seems to be swapped
112
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
113
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
114
        //icub handles eyes differently, we have to set pan angle + vergence
115
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
116
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
117
        //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);
118

119
        store_joint(ICUB_ID_EYES_PAN, pan);
120
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
121
    }else{
122
        store_joint(id, joint_target[e]);
123
    }
124
    #endif
125
}
126

127

128
//! actually execute the scheduled motion commands
129
void MekaJointInterface::execute_motion(){
130
    //build msg
131
    trajectory_msgs::JointTrajectory msg;
132
    msg.joint_names.push_back("head_j0");
133
    msg.joint_names.push_back("head_j1");
134

135
    trajectory_msgs::JointTrajectoryPoint p;
136
    p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0);
137
    p.positions.push_back(joint_target[ID_NECK_PAN] * M_PI / 180.0);
138

139
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
140
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
141

142
    msg.points.push_back(p);
143

144
    target_publisher.publish(msg);
145

146
    /*
147
     void MekaJointInterface::store_min_max(int id, float min, float max){
148
header:
149
  seq: 636
150
  stamp:
151
    secs: 0
152
    nsecs: 0
153
  frame_id: ''
154
joint_names: ['head_j0', 'head_j1']
155
points:
156
  -
157
    positions: [-0.31, 0.01954768762234005]
158
    velocities: []
159
    accelerations: []
160
    effort: []
161
    time_from_start:
162
      secs: 1
163
      nsecs: 0
164

165
     */
166

167
    #if 0
168
    // set up neck and eye motion commands:
169
    if (POSITION_CONTROL){
170
        //position control
171
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
172
            set_target_in_positionmode(i, target_angle[i]);
173
        }
174
    }else{
175
        //velocity control
176
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
177
            set_target_in_velocitymode(i, target_angle[i]);
178
        }
179
    }
180
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
181

182

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

186
    //eyebrows are set using a special command as well:
187
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
188
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
189

190
    //mouth
191
    set_mouth();
192

193
    #endif
194
}
195

196

197
//! prepare and enable a joint
198
//! NOTE: this should also prefill the min/max positions for this joint
199
//! \param the enum id of a joint
200
void MekaJointInterface::enable_joint(int e){
201
#if 0
202
    //FIXME ADD THIS:
203
    // enable the amplifier and the pid controller on each joint
204
    /*for (i = 0; i < nj; i++) {
205
       amp->enableAmp(i);
206
       pid->enablePid(i);
207
    }*/
208

209

210
    //set up smooth motion controller
211
    //step1: set up framerate
212
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
213

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

218
    //step3: set pid controller:
219
    /*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)){
220
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
221
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
222
    }*/
223

224
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
225

226
    //check if setting pid controllertype was successfull:
227
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
228
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
229
        exit(1);
230
    }*/
231

232
    //fetch min/max:
233
   // init_joint(e);
234

235
    //ok fine, now enable motor:
236
    //printf("> enabling motor %s\n", joint_name.c_str());
237
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
238
#endif
239
}
240

    
241
//! shutdown and disable a joint
242
//! \param the enum id of a joint
243
void MekaJointInterface::disable_joint(int e){
244
    /*
245
        //first: convert humotion enum to our enum:
246
        int motor_id = convert_enum_to_motorid(e);
247
        if (motor_id == -1){
248
            return; //we are not interested in that data, so we just return here
249
        }
250

251
        //fetch device:
252
        Device *dev = get_device(motor_id);
253
        printf("> FIXME: ADD DISABLE CODE\n");
254
        printf("> FIXME: ADD DISABLE CODE\n");
255
        printf("> FIXME: ADD DISABLE CODE\n");
256
        printf("> FIXME: ADD DISABLE CODE\n");
257
        printf("> FIXME: ADD DISABLE CODE\n");
258
        printf("> FIXME: ADD DISABLE CODE\n");
259
        printf("> FIXME: ADD DISABLE CODE\n");
260
        printf("> FIXME: ADD DISABLE CODE\n");
261
        printf("> FIXME: ADD DISABLE CODE\n");
262
        */
263
}
264

    
265
void MekaJointInterface::store_min_max(int id, float min, float max){
266
    joint_min[id] = min;
267
    joint_max[id] = max;
268
}
269

    
270
void MekaJointInterface::init_joints(){
271
    store_min_max(ID_NECK_TILT, -10, 10);
272
    store_min_max(ID_NECK_PAN, -10, 10);
273

    
274
    store_min_max(ID_NECK_ROLL, -1, 1);
275
    store_min_max(ID_EYES_BOTH_UD, -1, 1);
276
    store_min_max(ID_EYES_LEFT_LR, -1, 1);
277
    store_min_max(ID_EYES_RIGHT_LR, -1, 1);
278
    store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1);
279
    store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1);
280
    store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1);
281
    store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1);
282
    store_min_max(ID_EYES_LEFT_BROW, -1, 1);
283
    store_min_max(ID_EYES_RIGHT_BROW, -1, 1);
284
    store_min_max(ID_LIP_CENTER_UPPER, -1, 1);
285
    store_min_max(ID_LIP_CENTER_LOWER, -1, 1);
286
    store_min_max(ID_LIP_LEFT_UPPER, -1, 1);
287
    store_min_max(ID_LIP_LEFT_LOWER, -1, 1);
288
    store_min_max(ID_LIP_RIGHT_UPPER, -1, 1);
289
    store_min_max(ID_LIP_RIGHT_LOWER, -1, 1);
290
}
291

    
292
#if 0
293

294
//! conversion table for humotion motor ids to our ids:
295
//! \param enum from JointInterface::JOINT_ID_ENUM
296
//! \return int value of motor id
297
int iCubJointInterface::convert_enum_to_motorid(int e){
298
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
299
    if(it == enum_id_bimap.right.end()) {
300
        //key does not exists, we are not interested in that dataset, return -1
301
        return -1;
302
    }
303
    return it->second;
304
}
305

306

307
//! conversion table for our ids to humotion motor ids:
308
//! \param  int value of motor id
309
//! \return enum from JointInterface::JOINT_ID_ENUM
310
int iCubJointInterface::convert_motorid_to_enum(int id){
311
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
312
    if(it == enum_id_bimap.left.end()) {
313
        //key does not exists, we are not interested in that dataset, return -1
314
        return -1;
315
    }
316
    return it->second;
317
}
318

319
//! special command to set eyelid angle
320
//! \param angle in degrees
321
void iCubJointInterface::set_eyelid_angle(double angle){
322
    if (emotion_port[0].getOutputCount()>0){
323
        //try to set the value based on the upper one
324
        //some guesses from the sim: S30 = 0° / S40 = 10°
325
        int opening = (25.0 + 0.8*angle);
326
        opening = min(48, max(24, opening));
327

328
        if (opening == lid_opening_previous){
329
            //no update necessary
330
            return;
331
        }
332

333
        lid_angle = angle;
334
        lid_opening_previous = opening;
335

336
        char buf[20];
337
        sprintf(buf, "S%2d", opening);
338

339
        //printf("> SETTING EYELID '%s' (%f -> %d)\n",buf,angle,opening);
340
        Bottle &cmd = emotion_port[0].prepare();
341
        cmd.clear();
342
        cmd.addString(buf);
343
        emotion_port[0].write();
344
    }else{
345
        printf("> ERROR: no icub emotion output\n");
346
        exit(EXIT_FAILURE);
347
    }
348
}
349

350
//! special command to set the eyebrow angle
351
//! \param id {0=left, 1=right)
352
//! \param angle in degrees
353
void iCubJointInterface::set_eyebrow_angle(int id){
354
    int port_id;
355
    if (id == ICUB_ID_EYES_LEFT_BROW){
356
        port_id = 1;
357
    }else{
358
        port_id = 2;
359
    }
360

361
    if (emotion_port[port_id].getOutputCount()>0){
362
        double angle = target_angle[id];
363
        int icub_val = 0;
364

365
        //swap rotation direction:
366
        if (id==ICUB_ID_EYES_LEFT_BROW) angle = -angle;
367

368
        //convert to icub representation
369
        if (angle < -20){
370
            icub_val = 1;
371
        }else if (angle<10){
372
            icub_val = 2;
373
        }else if (angle<20){
374
            icub_val = 4;
375
        }else{
376
            icub_val = 8;
377
        }
378

379
        //make sure to update only on new values:
380
        if (icub_val == target_angle_previous[id]){
381
                //no updata necessary
382
                return;
383
        }
384

385
        //store actual value:
386
        target_angle_previous[id] = icub_val;
387

388

389
        string cmd_s;
390
        if (id==ICUB_ID_EYES_LEFT_BROW){
391
            cmd_s = "L0" + to_string(icub_val);
392
        }else{
393
            cmd_s = "R0" + to_string(icub_val);
394
        }
395

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

398
        Bottle &cmd = emotion_port[port_id].prepare();
399
        cmd.clear();
400
        cmd.addString(cmd_s);
401
        emotion_port[port_id].write();
402
    }else{
403
        printf("> ERROR: no icub emotion output\n");
404
        exit(EXIT_FAILURE);
405
    }
406
}
407

408
void iCubJointInterface::run(){
409
    iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
410
    data_receiver->start();
411
}
412

413
//! set the target position of a joint
414
//! \param enum id of joint
415
//! \param float value
416
void iCubJointInterface::publish_target_position(int e){
417
    //first: convert humotion enum to our enum:
418
    int id = convert_enum_to_motorid(e);
419
    if (id == -1){
420
        return; //we are not interested in that data, so we just return here
421
    }
422

423
    if (id == ICUB_ID_NECK_PAN){
424
        //PAN seems to be swapped
425
        store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
426
    }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
427
        //icub handles eyes differently, we have to set pan angle + vergence
428
        float pan      = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
429
        float vergence = (joint_target[ID_EYES_LEFT_LR]  - joint_target[ID_EYES_RIGHT_LR]);
430
        //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);
431

432
        store_joint(ICUB_ID_EYES_PAN, pan);
433
        store_joint(ICUB_ID_EYES_VERGENCE, vergence);
434
    }else{
435
        store_joint(id, joint_target[e]);
436
    }
437
}
438

439

440
//! set the target position of a joint
441
//! \param id of joint
442
//! \param float value of position
443
void iCubJointInterface::store_joint(int id, float value){
444
    //printf("> set joint %d = %f\n",id,value);
445
    target_angle[id] = value;
446
    //ipos->positionMove(id, value);
447
}
448

449
//! execute a move in position mode
450
//! \param id of joint
451
//! \param angle
452
void iCubJointInterface::set_target_in_positionmode(int id, double value){
453
    if (id>ICUB_ID_EYES_VERGENCE){
454
        printf("> ERROR: set_target_positionmode(id=%d, %3.2f) not supported for this id\n",id,value);
455
        return;
456
    }
457
#if 0
458
    //set speed cacluated as in velocity + set position -> replicates smoothmotion from flobi?!
459

460
    //first: calculate necessary speed to reach the given target within the next clock tick:
461
    double distance = value - target_angle_previous[id];
462
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
463
    //calculate speed for that:
464
    double speed = 0.85 * distance * ((double)MAIN_LOOP_FREQUENCY);
465

466
    //set up speed for controller:
467
    ipos->setRefSpeed(id, speed);
468
#endif
469
    //execute motion
470
    ipos->positionMove(id, value);
471
}
472

    
473
//! execute a move in velocity mode
474
//! \param id of joint
475
//! \param angle
476
void iCubJointInterface::set_target_in_velocitymode(int id, double value){
477
    //first: calculate necessary speed to reach the given target within the next clock tick:
478
    double distance = value - target_angle_previous[id];
479
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
480
    distance = 0.85 * distance;
481
    //calculate speed
482
    double speed = distance * ((double)MAIN_LOOP_FREQUENCY);
483
    //execute:
484
    ivel->velocityMove(id, speed);
485
    //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);
486

    
487
    target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value();
488
}
489

    
490
//! actually execute the scheduled motion commands
491
void iCubJointInterface::execute_motion(){
492

    
493
    // set up neck and eye motion commands:
494
    if (POSITION_CONTROL){
495
        //position control
496
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
497
            set_target_in_positionmode(i, target_angle[i]);
498
        }
499
    }else{
500
        //velocity control
501
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
502
            set_target_in_velocitymode(i, target_angle[i]);
503
        }
504
    }
505
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
506

    
507

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

    
511
    //eyebrows are set using a special command as well:
512
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
513
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
514

    
515
    //mouth
516
    set_mouth();
517

    
518

    
519
}
520

    
521
void iCubJointInterface::set_mouth(){
522
    //convert from 6DOF mouth displacement to icub leds:
523
    int led_value = 0;
524

    
525
    //fetch center opening:
526
    double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
527
    bool mouth_open = (center_opening>15.0)?true:false;
528

    
529
    //side of mouth high or low?
530
    double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0;
531
    double left_avg   = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0;
532
    double right_avg  = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0;
533

    
534
    //happy, neutral or sad?
535
    double diff_l = center_avg - left_avg;
536
    double diff_r = center_avg - right_avg;
537
    double diff   = (diff_l+diff_r)/2.0;
538

    
539
    if (diff > 2.0){
540
        if (mouth_open){
541
            led_value = 0x14;
542
        }else{
543
            if (diff > 2.6){
544
                led_value = 0x0A;
545
            }else{
546
                led_value = 0x0B;
547
            }
548
        }
549
    }else if (diff < -3.0){
550
        if (mouth_open){
551
            led_value = 0x06;
552
        }else{
553
            led_value = 0x18;
554
        }
555
    }else if (diff < -2.0){
556
        if (mouth_open){
557
            led_value = 0x04; //0x25;
558
        }else{
559
            led_value = 0x08;
560
        }
561
    }else{
562
        if (mouth_open){
563
            led_value = 0x16;
564
        }else{
565
            led_value = 0x08;
566
        }
567
    }
568

    
569

    
570
    if (led_value == previous_mouth_state){
571
        //no update necessary
572
        return;
573
    }
574

    
575
    previous_mouth_state = led_value;
576

    
577
    //convert to string:
578
    char buf[10];
579
    sprintf(buf, "M%02X",led_value);
580

    
581
    /*printf("> sending mouth '%s'\n",buf);
582
    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]);
583
    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]);
584
    printf("  mouth  open=%3.2f diff=%3.2f\n", center_opening, diff);*/
585

    
586
    //add mouth:
587
    Bottle &cmd = emotion_port[3].prepare();
588
    cmd.clear();
589
    cmd.addString(buf);
590
    emotion_port[3].write();
591

    
592

    
593
    //store joint values which we do not handle on icub here:
594
    double timestamp = get_timestamp_ms();
595
    JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER,   target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp);
596
    JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER,   target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp);
597
    JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp);
598
    JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp);
599
    JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER,  target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp);
600
    JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER,  target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp);
601

    
602
}
603

    
604
double iCubJointInterface::get_timestamp_ms(){
605
    struct timespec spec;
606
    clock_gettime(CLOCK_REALTIME, &spec);
607
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
608
}
609

    
610
//! set the current position of a joint
611
//! \param id of joint
612
//! \param float value of position
613
//! \param double timestamp
614
void iCubJointInterface::fetch_position(int id, double value, double timestamp){
615
    //store joint based on id:
616
    switch(id){
617
        default:
618
            printf("> ERROR: unhandled joint id %d\n",id);
619
            return;
620

    
621
        case(100):
622
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp);
623
            break;
624

    
625
        case(2):
626
            //PAN is inverted!
627
            JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp);
628
            break;
629

    
630
        case(0):
631
            JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp);
632
            break;
633

    
634
        case(1):
635
            JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp);
636
            break;
637

    
638
        case(3):
639
            JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp);
640
            break;
641

    
642
        //icub handles eyes differently, we have to set pan angle + vergence
643
        case(4): {//pan
644
            last_pos_eye_pan = value;
645
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
646
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
647

    
648
            //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);
649
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
650
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
651
            break;
652
        }
653

    
654
        case(5): { //vergence
655
            last_pos_eye_vergence = value;
656
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
657
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
658

    
659
            //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);
660
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
661
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
662
            break;
663
        }
664
    }
665

    
666

    
667
}
668

    
669
//! set the current speed of a joint
670
//! \param enum id of joint
671
//! \param float value of speed
672
//! \param double timestamp
673
void iCubJointInterface::fetch_speed(int id, double value, double timestamp){
674

    
675
    switch(id){
676
        default:
677
            printf("> ERROR: unhandled joint id %d\n",id);
678
            return;
679

    
680
        case(2):
681
            JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp);
682
            break;
683

    
684
        case(0):
685
            JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp);
686
            break;
687

    
688
        case(1):
689
            JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp);
690
            break;
691

    
692
        case(3):
693
            JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp);
694
            break;
695

    
696
        //icub handles eyes differently, we have to set pan angle + vergence
697
        case(4): {//pan
698
            last_vel_eye_pan = value;
699
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
700
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
701

    
702
            //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);
703
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
704
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
705
            break;
706
        }
707

    
708
        case(5): { //vergence
709
            last_vel_eye_pan = value;
710
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
711
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
712

    
713
            //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);
714
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
715
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
716
            break;
717
        }
718
    }
719
/*
720
    JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
721
    JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
722
    JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
723
    JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
724
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
725
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
726

727
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_LOWER, 0.0, timestamp);
728
    JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_UPPER, 0.0, timestamp);
729
    JointInterface::store_incoming_speed(ID_EYES_LEFT_BROW, 0.0, timestamp);
730

731
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_LOWER, 0.0, timestamp);
732
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_UPPER,0.0, timestamp);
733
    JointInterface::store_incoming_speed(ID_EYES_RIGHT_BROW, 0.0, timestamp);*/
734
    /*
735
    //fetch enum id:
736
    int e = convert_motorid_to_enum(device->get_device_id());
737
    if (e == -1){
738
        return; //we are not interested in that data, so we just return here
739
    }
740

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

    
743
}
744
/*
745
//! conversion table for humotion motor ids to our ids:
746
//! \param enum from JointInterface::JOINT_ID_ENUM
747
//! \return int value of motor id
748
int HumotionJointInterface::convert_enum_to_motorid(int e){
749
    enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
750
    if(it == enum_id_bimap.right.end()) {
751
        //key does not exists, we are not interested in that dataset, return -1
752
        return -1;
753
    }
754

755
    return it->second;
756
}
757

758

759
//! conversion table for our ids to humotion motor ids:
760
//! \param  int value of motor id
761
//! \return enum from JointInterface::JOINT_ID_ENUM
762
int HumotionJointInterface::convert_motorid_to_enum(int id){
763
    enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
764
    if(it == enum_id_bimap.left.end()) {
765
        //key does not exists, we are not interested in that dataset, return -1
766
        return -1;
767
    }
768

769
    return it->second;
770
}
771
*/
772

    
773
//! prepare and enable a joint
774
//! NOTE: this should also prefill the min/max positions for this joint
775
//! \param the enum id of a joint
776
void iCubJointInterface::enable_joint(int e){
777
    //FIXME ADD THIS:
778
    // enable the amplifier and the pid controller on each joint
779
    /*for (i = 0; i < nj; i++) {
780
       amp->enableAmp(i);
781
       pid->enablePid(i);
782
    }*/
783

    
784

    
785
    //set up smooth motion controller
786
    //step1: set up framerate
787
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
788

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

    
793
    //step3: set pid controller:
794
    /*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)){
795
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
796
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
797
    }*/
798

    
799
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
800

    
801
    //check if setting pid controllertype was successfull:
802
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
803
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
804
        exit(1);
805
    }*/
806

    
807
    //fetch min/max:
808
   // init_joint(e);
809

    
810
    //ok fine, now enable motor:
811
    //printf("> enabling motor %s\n", joint_name.c_str());
812
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
813

    
814
}
815

    
816
void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){
817
    double min, max;
818
    ilimits->getLimits(id, &min, &max);
819
    joint_min[e] = min;
820
    joint_max[e] = max;
821
}
822

    
823
//! initialise a joint (set up controller mode etc)
824
//! \param joint enum
825
void iCubJointInterface::init_joints(){
826
    store_min_max(ilimits, 0, ID_NECK_TILT);
827
    store_min_max(ilimits, 1, ID_NECK_ROLL);
828
    store_min_max(ilimits, 2, ID_NECK_PAN);
829
    store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
830

    
831
    //icub handles eyes differently, we have to set pan angle + vergence
832
    double pan_min, pan_max, vergence_min, vergence_max;
833
    ilimits->getLimits(4, &pan_min, &pan_max);
834
    ilimits->getLimits(5, &vergence_min, &vergence_max);
835

    
836
    //this is not 100% correct, should be fixed:
837
    joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
838
    joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
839
    joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR];
840
    joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR];
841

    
842
    //eyelids:
843
    joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30;
844
    joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30;
845
    lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
846

    
847
    //eyebrows:
848
    joint_min[ID_EYES_LEFT_BROW] = -50;
849
    joint_max[ID_EYES_LEFT_BROW] = 50;
850
    joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW];
851
    joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW];
852

    
853
    //mouth:
854
    joint_min[ID_LIP_CENTER_UPPER] = 5;
855
    joint_max[ID_LIP_CENTER_UPPER] = 50;
856
    joint_min[ID_LIP_CENTER_LOWER] = 5;
857
    joint_max[ID_LIP_CENTER_LOWER] = 50;
858
    joint_min[ID_LIP_LEFT_UPPER] = 5;
859
    joint_max[ID_LIP_LEFT_UPPER] = 50;
860
    joint_min[ID_LIP_LEFT_LOWER] = 5;
861
    joint_max[ID_LIP_LEFT_LOWER] = 50;
862
    joint_min[ID_LIP_RIGHT_UPPER] = 5;
863
    joint_max[ID_LIP_RIGHT_UPPER] = 50;
864
    joint_min[ID_LIP_RIGHT_LOWER] = 5;
865
    joint_max[ID_LIP_RIGHT_LOWER] = 50;
866

    
867

    
868
}
869

    
870
//! shutdown and disable a joint
871
//! \param the enum id of a joint
872
void iCubJointInterface::disable_joint(int e){
873
    /*
874
        //first: convert humotion enum to our enum:
875
        int motor_id = convert_enum_to_motorid(e);
876
        if (motor_id == -1){
877
            return; //we are not interested in that data, so we just return here
878
        }
879

880
        //fetch device:
881
        Device *dev = get_device(motor_id);
882
        printf("> FIXME: ADD DISABLE CODE\n");
883
        printf("> FIXME: ADD DISABLE CODE\n");
884
        printf("> FIXME: ADD DISABLE CODE\n");
885
        printf("> FIXME: ADD DISABLE CODE\n");
886
        printf("> FIXME: ADD DISABLE CODE\n");
887
        printf("> FIXME: ADD DISABLE CODE\n");
888
        printf("> FIXME: ADD DISABLE CODE\n");
889
        printf("> FIXME: ADD DISABLE CODE\n");
890
        printf("> FIXME: ADD DISABLE CODE\n");
891
        */
892
}
893
#endif