Statistics
| Branch: | Tag: | Revision:

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

History | View | Annotate | Download (30.825 KB)

1 2be6243f Sebastian Meyer zu Borgsen
#include "mekajointinterface.h"
2
using namespace std;
3
4
//WARNING: DO NOT CHANGE THIS; VELOCITYMODE IS NOT YET IMPLEMENTED
5
#define POSITION_CONTROL 1
6
7 473a6a6c Simon Schulz
void MekaJointInterface::incoming_jointstates(const sensor_msgs::JointState & msg){
8 a4795834 Simon Schulz
    //fetch current timestamp
9
    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 e8e20dfe Sebastian Meyer zu Borgsen
        if (name == "head_j1"){
18 a4795834 Simon Schulz
            id = ID_NECK_PAN;
19 e8e20dfe Sebastian Meyer zu Borgsen
        }else if(name == "head_j0"){
20 a4795834 Simon Schulz
            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 473a6a6c Simon Schulz
}
56
57 2be6243f Sebastian Meyer zu Borgsen
//! constructor
58 e4bb9fd4 Simon Schulz
MekaJointInterface::MekaJointInterface(string _input_scope, string _output_scope) : humotion::server::JointInterface(){
59
    input_scope = _input_scope;
60
    output_scope = _output_scope;
61 2be6243f Sebastian Meyer zu Borgsen
62 473a6a6c Simon Schulz
    //subscribe to meka joint states
63 99ebae32 Simon Schulz
    int argc = 0;
64
    ros::init(argc, (char**)NULL, "meka_humotion");
65 473a6a6c Simon Schulz
    ros::NodeHandle n;
66 2be6243f Sebastian Meyer zu Borgsen
67
68 e4bb9fd4 Simon Schulz
    printf("> listening on jointstates on '%s'\n",input_scope.c_str());
69
    joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates , this);
70 2be6243f Sebastian Meyer zu Borgsen
71 e4bb9fd4 Simon Schulz
    printf("> sending targets on '%s'\n", output_scope.c_str());
72
    target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
73 2be6243f Sebastian Meyer zu Borgsen
74
75 a4795834 Simon Schulz
    //tell humotion about min/max joint values:
76
    init_joints();
77 2be6243f Sebastian Meyer zu Borgsen
}
78
79
//! destructor
80
MekaJointInterface::~MekaJointInterface(){
81
}
82
83 473a6a6c Simon Schulz
84
85
void MekaJointInterface::run(){
86
   //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
87
   //data_receiver->start();
88 a4795834 Simon Schulz
   ros::spin();
89 473a6a6c Simon Schulz
}
90
91
92 a4795834 Simon Schulz
double MekaJointInterface::get_timestamp_ms(){
93
    struct timespec spec;
94
    clock_gettime(CLOCK_REALTIME, &spec);
95
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
96
}
97
98 473a6a6c Simon Schulz
//! set the target position of a joint
99
//! \param enum id of joint
100
//! \param float value
101
void MekaJointInterface::publish_target_position(int e){
102
    #if 0
103
    //first: convert humotion enum to our enum:
104
    int id = convert_enum_to_motorid(e);
105
    if (id == -1){
106
        return; //we are not interested in that data, so we just return here
107
    }
108

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

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

126

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

134 e8e20dfe Sebastian Meyer zu Borgsen
    trajectory_msgs::JointTrajectoryPoint p;
135
    p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0);
136
    p.positions.push_back(joint_target[ID_NECK_PAN] * M_PI / 180.0);
137 a4795834 Simon Schulz

138 e8e20dfe Sebastian Meyer zu Borgsen
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
139
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
140 a4795834 Simon Schulz

141 e8e20dfe Sebastian Meyer zu Borgsen
    msg.points.push_back(p);
142 a4795834 Simon Schulz

143
    target_publisher.publish(msg);
144

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

164
     */
165

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

181

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

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

189
    //mouth
190
    set_mouth();
191

192
    #endif
193
}
194

195

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

208

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

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

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

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

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

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

234
    //ok fine, now enable motor:
235
    //printf("> enabling motor %s\n", joint_name.c_str());
236
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
237
#endif
238
}
239
240
//! shutdown and disable a joint
241
//! \param the enum id of a joint
242
void MekaJointInterface::disable_joint(int e){
243
    /*
244
        //first: convert humotion enum to our enum:
245
        int motor_id = convert_enum_to_motorid(e);
246
        if (motor_id == -1){
247
            return; //we are not interested in that data, so we just return here
248
        }
249

250
        //fetch device:
251
        Device *dev = get_device(motor_id);
252
        printf("> FIXME: ADD DISABLE CODE\n");
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
        */
262
}
263
264 a4795834 Simon Schulz
void MekaJointInterface::store_min_max(int id, float min, float max){
265
    joint_min[id] = min;
266
    joint_max[id] = max;
267
}
268
269
void MekaJointInterface::init_joints(){
270
    store_min_max(ID_NECK_TILT, -10, 10);
271
    store_min_max(ID_NECK_PAN, -10, 10);
272
273
    store_min_max(ID_NECK_ROLL, -1, 1);
274
    store_min_max(ID_EYES_BOTH_UD, -1, 1);
275
    store_min_max(ID_EYES_LEFT_LR, -1, 1);
276
    store_min_max(ID_EYES_RIGHT_LR, -1, 1);
277
    store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1);
278
    store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1);
279
    store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1);
280
    store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1);
281
    store_min_max(ID_EYES_LEFT_BROW, -1, 1);
282
    store_min_max(ID_EYES_RIGHT_BROW, -1, 1);
283
    store_min_max(ID_LIP_CENTER_UPPER, -1, 1);
284
    store_min_max(ID_LIP_CENTER_LOWER, -1, 1);
285
    store_min_max(ID_LIP_LEFT_UPPER, -1, 1);
286
    store_min_max(ID_LIP_LEFT_LOWER, -1, 1);
287
    store_min_max(ID_LIP_RIGHT_UPPER, -1, 1);
288
    store_min_max(ID_LIP_RIGHT_LOWER, -1, 1);
289
}
290
291 473a6a6c Simon Schulz
#if 0
292 2be6243f Sebastian Meyer zu Borgsen

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

305

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

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

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

332
        lid_angle = angle;
333
        lid_opening_previous = opening;
334

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

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

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

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

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

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

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

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

387

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

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

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

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

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

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

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

438

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

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

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

465
    //set up speed for controller:
466
    ipos->setRefSpeed(id, speed);
467
#endif
468
    //execute motion
469
    ipos->positionMove(id, value);
470
}
471
472
//! execute a move in velocity mode
473
//! \param id of joint
474
//! \param angle
475
void iCubJointInterface::set_target_in_velocitymode(int id, double value){
476
    //first: calculate necessary speed to reach the given target within the next clock tick:
477
    double distance = value - target_angle_previous[id];
478
    //make the motion smooth: we want to reach 85% of the target in the next iteration:
479
    distance = 0.85 * distance;
480
    //calculate speed
481
    double speed = distance * ((double)MAIN_LOOP_FREQUENCY);
482
    //execute:
483
    ivel->velocityMove(id, speed);
484
    //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);
485
486
    target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value();
487
}
488
489
//! actually execute the scheduled motion commands
490
void iCubJointInterface::execute_motion(){
491
492
    // set up neck and eye motion commands:
493
    if (POSITION_CONTROL){
494
        //position control
495
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
496
            set_target_in_positionmode(i, target_angle[i]);
497
        }
498
    }else{
499
        //velocity control
500
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
501
            set_target_in_velocitymode(i, target_angle[i]);
502
        }
503
    }
504
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
505
506
507
    //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
508
    set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
509
510
    //eyebrows are set using a special command as well:
511
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
512
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
513
514
    //mouth
515
    set_mouth();
516
517
518
}
519
520
void iCubJointInterface::set_mouth(){
521
    //convert from 6DOF mouth displacement to icub leds:
522
    int led_value = 0;
523
524
    //fetch center opening:
525
    double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
526
    bool mouth_open = (center_opening>15.0)?true:false;
527
528
    //side of mouth high or low?
529
    double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0;
530
    double left_avg   = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0;
531
    double right_avg  = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0;
532
533
    //happy, neutral or sad?
534
    double diff_l = center_avg - left_avg;
535
    double diff_r = center_avg - right_avg;
536
    double diff   = (diff_l+diff_r)/2.0;
537
538
    if (diff > 2.0){
539
        if (mouth_open){
540
            led_value = 0x14;
541
        }else{
542
            if (diff > 2.6){
543
                led_value = 0x0A;
544
            }else{
545
                led_value = 0x0B;
546
            }
547
        }
548
    }else if (diff < -3.0){
549
        if (mouth_open){
550
            led_value = 0x06;
551
        }else{
552
            led_value = 0x18;
553
        }
554
    }else if (diff < -2.0){
555
        if (mouth_open){
556
            led_value = 0x04; //0x25;
557
        }else{
558
            led_value = 0x08;
559
        }
560
    }else{
561
        if (mouth_open){
562
            led_value = 0x16;
563
        }else{
564
            led_value = 0x08;
565
        }
566
    }
567
568
569
    if (led_value == previous_mouth_state){
570
        //no update necessary
571
        return;
572
    }
573
574
    previous_mouth_state = led_value;
575
576
    //convert to string:
577
    char buf[10];
578
    sprintf(buf, "M%02X",led_value);
579
580
    /*printf("> sending mouth '%s'\n",buf);
581
    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]);
582
    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]);
583
    printf("  mouth  open=%3.2f diff=%3.2f\n", center_opening, diff);*/
584
585
    //add mouth:
586
    Bottle &cmd = emotion_port[3].prepare();
587
    cmd.clear();
588
    cmd.addString(buf);
589
    emotion_port[3].write();
590
591
592
    //store joint values which we do not handle on icub here:
593
    double timestamp = get_timestamp_ms();
594
    JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER,   target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp);
595
    JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER,   target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp);
596
    JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp);
597
    JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp);
598
    JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER,  target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp);
599
    JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER,  target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp);
600
601
}
602
603
double iCubJointInterface::get_timestamp_ms(){
604
    struct timespec spec;
605
    clock_gettime(CLOCK_REALTIME, &spec);
606
    return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6;
607
}
608
609
//! set the current position of a joint
610
//! \param id of joint
611
//! \param float value of position
612
//! \param double timestamp
613
void iCubJointInterface::fetch_position(int id, double value, double timestamp){
614
    //store joint based on id:
615
    switch(id){
616
        default:
617
            printf("> ERROR: unhandled joint id %d\n",id);
618
            return;
619
620
        case(100):
621
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp);
622
            break;
623
624
        case(2):
625
            //PAN is inverted!
626
            JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp);
627
            break;
628
629
        case(0):
630
            JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp);
631
            break;
632
633
        case(1):
634
            JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp);
635
            break;
636
637
        case(3):
638
            JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp);
639
            break;
640
641
        //icub handles eyes differently, we have to set pan angle + vergence
642
        case(4): {//pan
643
            last_pos_eye_pan = value;
644
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
645
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
646
647
            //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);
648
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
649
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
650
            break;
651
        }
652
653
        case(5): { //vergence
654
            last_pos_eye_vergence = value;
655
            float left  = last_pos_eye_pan + last_pos_eye_vergence/2.0;
656
            float right = last_pos_eye_pan - last_pos_eye_vergence/2.0;
657
658
            //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);
659
            JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp);
660
            JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp);
661
            break;
662
        }
663
    }
664
665
666
}
667
668
//! set the current speed of a joint
669
//! \param enum id of joint
670
//! \param float value of speed
671
//! \param double timestamp
672
void iCubJointInterface::fetch_speed(int id, double value, double timestamp){
673
674
    switch(id){
675
        default:
676
            printf("> ERROR: unhandled joint id %d\n",id);
677
            return;
678
679
        case(2):
680
            JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp);
681
            break;
682
683
        case(0):
684
            JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp);
685
            break;
686
687
        case(1):
688
            JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp);
689
            break;
690
691
        case(3):
692
            JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp);
693
            break;
694
695
        //icub handles eyes differently, we have to set pan angle + vergence
696
        case(4): {//pan
697
            last_vel_eye_pan = value;
698
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
699
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
700
701
            //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);
702
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
703
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
704
            break;
705
        }
706
707
        case(5): { //vergence
708
            last_vel_eye_pan = value;
709
            float left  = last_vel_eye_pan + last_vel_eye_vergence/2.0;
710
            float right = last_vel_eye_pan - last_vel_eye_vergence/2.0;
711
712
            //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);
713
            JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp);
714
            JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp);
715
            break;
716
        }
717
    }
718
/*
719
    JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
720
    JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
721
    JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
722
    JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
723
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
724
    JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
725

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

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

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

754
    return it->second;
755
}
756

757

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

768
    return it->second;
769
}
770
*/
771
772
//! prepare and enable a joint
773
//! NOTE: this should also prefill the min/max positions for this joint
774
//! \param the enum id of a joint
775
void iCubJointInterface::enable_joint(int e){
776
    //FIXME ADD THIS:
777
    // enable the amplifier and the pid controller on each joint
778
    /*for (i = 0; i < nj; i++) {
779
       amp->enableAmp(i);
780
       pid->enablePid(i);
781
    }*/
782
783
784
    //set up smooth motion controller
785
    //step1: set up framerate
786
    //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
787
788
    //step2: set controllertype:
789
    //printf("> activating smooth motion control for joint id 0x%02X (%s)\n", motor_id, joint_name.c_str());
790
    //dev->set_register_blocking(XSC3_REGISTER_PID_CONTROLLER, XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK, true);
791
792
    //step3: set pid controller:
793
    /*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)){
794
        printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
795
        dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
796
    }*/
797
798
    //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
799
800
    //check if setting pid controllertype was successfull:
801
    /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
802
        printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
803
        exit(1);
804
    }*/
805
806
    //fetch min/max:
807
   // init_joint(e);
808
809
    //ok fine, now enable motor:
810
    //printf("> enabling motor %s\n", joint_name.c_str());
811
    //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
812
813
}
814
815
void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){
816
    double min, max;
817
    ilimits->getLimits(id, &min, &max);
818
    joint_min[e] = min;
819
    joint_max[e] = max;
820
}
821
822
//! initialise a joint (set up controller mode etc)
823
//! \param joint enum
824
void iCubJointInterface::init_joints(){
825
    store_min_max(ilimits, 0, ID_NECK_TILT);
826
    store_min_max(ilimits, 1, ID_NECK_ROLL);
827
    store_min_max(ilimits, 2, ID_NECK_PAN);
828
    store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
829
830
    //icub handles eyes differently, we have to set pan angle + vergence
831
    double pan_min, pan_max, vergence_min, vergence_max;
832
    ilimits->getLimits(4, &pan_min, &pan_max);
833
    ilimits->getLimits(5, &vergence_min, &vergence_max);
834
835
    //this is not 100% correct, should be fixed:
836
    joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
837
    joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
838
    joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR];
839
    joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR];
840
841
    //eyelids:
842
    joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30;
843
    joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30;
844
    lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
845
846
    //eyebrows:
847
    joint_min[ID_EYES_LEFT_BROW] = -50;
848
    joint_max[ID_EYES_LEFT_BROW] = 50;
849
    joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW];
850
    joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW];
851
852
    //mouth:
853
    joint_min[ID_LIP_CENTER_UPPER] = 5;
854
    joint_max[ID_LIP_CENTER_UPPER] = 50;
855
    joint_min[ID_LIP_CENTER_LOWER] = 5;
856
    joint_max[ID_LIP_CENTER_LOWER] = 50;
857
    joint_min[ID_LIP_LEFT_UPPER] = 5;
858
    joint_max[ID_LIP_LEFT_UPPER] = 50;
859
    joint_min[ID_LIP_LEFT_LOWER] = 5;
860
    joint_max[ID_LIP_LEFT_LOWER] = 50;
861
    joint_min[ID_LIP_RIGHT_UPPER] = 5;
862
    joint_max[ID_LIP_RIGHT_UPPER] = 50;
863
    joint_min[ID_LIP_RIGHT_LOWER] = 5;
864
    joint_max[ID_LIP_RIGHT_LOWER] = 50;
865
866
867
}
868
869
//! shutdown and disable a joint
870
//! \param the enum id of a joint
871
void iCubJointInterface::disable_joint(int e){
872
    /*
873
        //first: convert humotion enum to our enum:
874
        int motor_id = convert_enum_to_motorid(e);
875
        if (motor_id == -1){
876
            return; //we are not interested in that data, so we just return here
877
        }
878

879
        //fetch device:
880
        Device *dev = get_device(motor_id);
881
        printf("> FIXME: ADD DISABLE CODE\n");
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
        */
891
}
892 473a6a6c Simon Schulz
#endif