humotion / examples / meka / src / mekajointinterface.cpp @ 3504a859
History | View | Annotate | Download (30.371 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 | //joint_pos_global = msg.position[3];
|
||
9 | cout << msg; |
||
10 | } |
||
11 | |||
12 | 2be6243f | Sebastian Meyer zu Borgsen | //! constructor
|
13 | MekaJointInterface::MekaJointInterface(string _scope) : humotion::server::JointInterface(){
|
||
14 | scope = _scope; |
||
15 | |||
16 | 473a6a6c | Simon Schulz | //subscribe to meka joint states
|
17 | 3504a859 | Simon Schulz | ros::init(); |
18 | 473a6a6c | Simon Schulz | ros::NodeHandle n; |
19 | joint_state_subscriber = n.subscribe(scope + "joint_states", 150, &MekaJointInterface::incoming_jointstates , this); |
||
20 | |||
21 | |||
22 | 2be6243f | Sebastian Meyer zu Borgsen | //add mapping from ids to enums:
|
23 | //this might look strange at the first sight but we need to have a generic
|
||
24 | //way to acces joints from libhumotion. therefore the lib uses its enum with ID_* enum ids
|
||
25 | //to access the joints. now we need to define a mapping to map those to our motor ids.
|
||
26 | //this is what we use the enum bimap for (convertion fro/to motorid is handled
|
||
27 | //by \sa convert_enum_to_motorid() and \sa convert_motorid_to_enum() lateron
|
||
28 | /*
|
||
29 | //MOUTH
|
||
30 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_UPPER, ID_LIP_LEFT_UPPER));
|
||
31 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_LEFT_LOWER, ID_LIP_LEFT_LOWER));
|
||
32 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_UPPER, ID_LIP_CENTER_UPPER));
|
||
33 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_CENTER_LOWER, ID_LIP_CENTER_LOWER));
|
||
34 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_UPPER, ID_LIP_RIGHT_UPPER));
|
||
35 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_LIP_RIGHT_LOWER, ID_LIP_RIGHT_LOWER));
|
||
36 | |||
37 | //NECK
|
||
38 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_PAN, ID_NECK_PAN));
|
||
39 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_TILT, ID_NECK_TILT));
|
||
40 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_NECK_ROLL, ID_NECK_ROLL));
|
||
41 | |||
42 | //EYES
|
||
43 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LR, ID_EYES_LEFT_LR));
|
||
44 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LR, ID_EYES_RIGHT_LR));
|
||
45 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_BOTH_UD, ID_EYES_BOTH_UD));
|
||
46 | |||
47 | //EYELIDS
|
||
48 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_LOWER, ID_EYES_LEFT_LID_LOWER));
|
||
49 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_LID_UPPER, ID_EYES_LEFT_LID_UPPER));
|
||
50 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_LEFT_BROW, ID_EYES_LEFT_BROW));
|
||
51 | |||
52 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_LOWER, ID_EYES_RIGHT_LID_LOWER));
|
||
53 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_LID_UPPER,ID_EYES_RIGHT_LID_UPPER));
|
||
54 | enum_id_bimap.insert(enum_id_bimap_entry_t(ICUB_ID_EYES_RIGHT_BROW, ID_EYES_RIGHT_BROW));
|
||
55 | |||
56 | Property options;
|
||
57 | options.put("device", "remote_controlboard");
|
||
58 | options.put("local", "/local/head");
|
||
59 | options.put("remote", scope+"/head");
|
||
60 | dd.open(options);
|
||
61 | |||
62 | //fetch views:
|
||
63 | dd.view(iencs);
|
||
64 | dd.view(ipos);
|
||
65 | dd.view(ivel);
|
||
66 | dd.view(ilimits);
|
||
67 | |||
68 | if ( (!iencs) || (!ipos) || (!ilimits) || (!ivel)){
|
||
69 | printf("> ERROR: failed to open icub views\n");
|
||
70 | exit(EXIT_FAILURE);
|
||
71 | }
|
||
72 | |||
73 | int joints;
|
||
74 | |||
75 | //tell humotion about min/max joint values:
|
||
76 | init_joints();
|
||
77 | |||
78 | iencs->getAxes(&joints);
|
||
79 | positions.resize(joints);
|
||
80 | velocities.resize(joints);
|
||
81 | commands.resize(joints);
|
||
82 | |||
83 | //set position mode:
|
||
84 | if (POSITION_CONTROL){
|
||
85 | commands=200000.0;
|
||
86 | ipos->setRefAccelerations(commands.data());
|
||
87 | ipos->setPositionMode();
|
||
88 | }else{
|
||
89 | ivel->setVelocityMode();
|
||
90 | commands=1000000;
|
||
91 | ivel->setRefAccelerations(commands.data());
|
||
92 | }
|
||
93 | |||
94 | //attach to facial expressions:
|
||
95 | string emotion_scope = scope + "/face/raw/in";
|
||
96 | printf("> opening connection to %s\n", emotion_scope.c_str());
|
||
97 | |||
98 | for(int i=0; i<4; i++){
|
||
99 | //strange, if we use one output port only the first command is executed?! flushing issues?
|
||
100 | string emotion_port_out = "/emotionwriter" + to_string(i);
|
||
101 | if (!emotion_port[i].open(emotion_port_out.c_str())){
|
||
102 | printf("> ERROR: failed to open to %s\n",emotion_port_out.c_str());
|
||
103 | exit(EXIT_FAILURE);
|
||
104 | }
|
||
105 | if (!Network::connect(emotion_port_out.c_str(), emotion_scope.c_str())){
|
||
106 | printf("> ERROR: failed to connect emotion ports\n");
|
||
107 | exit(EXIT_FAILURE);
|
||
108 | }
|
||
109 | }
|
||
110 | */
|
||
111 | } |
||
112 | |||
113 | //! destructor
|
||
114 | MekaJointInterface::~MekaJointInterface(){ |
||
115 | } |
||
116 | |||
117 | 473a6a6c | Simon Schulz | |
118 | |||
119 | void MekaJointInterface::run(){
|
||
120 | //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
|
||
121 | //data_receiver->start();
|
||
122 | } |
||
123 | |||
124 | |||
125 | //! set the target position of a joint
|
||
126 | //! \param enum id of joint
|
||
127 | //! \param float value
|
||
128 | void MekaJointInterface::publish_target_position(int e){ |
||
129 | #if 0
|
||
130 | //first: convert humotion enum to our enum:
|
||
131 | int id = convert_enum_to_motorid(e);
|
||
132 | if (id == -1){
|
||
133 | return; //we are not interested in that data, so we just return here
|
||
134 | }
|
||
135 | |||
136 | if (id == ICUB_ID_NECK_PAN){
|
||
137 | //PAN seems to be swapped
|
||
138 | store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
|
||
139 | }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
|
||
140 | //icub handles eyes differently, we have to set pan angle + vergence
|
||
141 | float pan = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
|
||
142 | float vergence = (joint_target[ID_EYES_LEFT_LR] - joint_target[ID_EYES_RIGHT_LR]);
|
||
143 | //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);
|
||
144 | |||
145 | store_joint(ICUB_ID_EYES_PAN, pan);
|
||
146 | store_joint(ICUB_ID_EYES_VERGENCE, vergence);
|
||
147 | }else{
|
||
148 | store_joint(id, joint_target[e]);
|
||
149 | }
|
||
150 | #endif
|
||
151 | }
|
||
152 | |||
153 | |||
154 | //! actually execute the scheduled motion commands
|
||
155 | void MekaJointInterface::execute_motion(){
|
||
156 | #if 0
|
||
157 | // set up neck and eye motion commands:
|
||
158 | if (POSITION_CONTROL){
|
||
159 | //position control
|
||
160 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
|
||
161 | set_target_in_positionmode(i, target_angle[i]);
|
||
162 | }
|
||
163 | }else{
|
||
164 | //velocity control
|
||
165 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
|
||
166 | set_target_in_velocitymode(i, target_angle[i]);
|
||
167 | }
|
||
168 | }
|
||
169 | //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
|
||
170 | |||
171 | |||
172 | //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
|
||
173 | set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
|
||
174 | |||
175 | //eyebrows are set using a special command as well:
|
||
176 | set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
|
||
177 | set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
|
||
178 | |||
179 | //mouth
|
||
180 | set_mouth();
|
||
181 | |||
182 | #endif
|
||
183 | }
|
||
184 | |||
185 | |||
186 | //! prepare and enable a joint
|
||
187 | //! NOTE: this should also prefill the min/max positions for this joint
|
||
188 | //! \param the enum id of a joint
|
||
189 | void MekaJointInterface::enable_joint(int e){
|
||
190 | #if 0
|
||
191 | //FIXME ADD THIS:
|
||
192 | // enable the amplifier and the pid controller on each joint
|
||
193 | /*for (i = 0; i < nj; i++) {
|
||
194 | amp->enableAmp(i);
|
||
195 | pid->enablePid(i);
|
||
196 | }*/
|
||
197 | |||
198 | |||
199 | //set up smooth motion controller
|
||
200 | //step1: set up framerate
|
||
201 | //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
|
||
202 | |||
203 | //step2: set controllertype:
|
||
204 | //printf("> activating smooth motion control for joint id 0x%02X (%s)\n", motor_id, joint_name.c_str());
|
||
205 | //dev->set_register_blocking(XSC3_REGISTER_PID_CONTROLLER, XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK, true);
|
||
206 | |||
207 | //step3: set pid controller:
|
||
208 | /*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)){
|
||
209 | printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
|
||
210 | dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
|
||
211 | }*/
|
||
212 | |||
213 | //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
|
||
214 | |||
215 | //check if setting pid controllertype was successfull:
|
||
216 | /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
|
||
217 | printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
|
||
218 | exit(1);
|
||
219 | }*/
|
||
220 | |||
221 | //fetch min/max:
|
||
222 | // init_joint(e);
|
||
223 | |||
224 | //ok fine, now enable motor:
|
||
225 | //printf("> enabling motor %s\n", joint_name.c_str());
|
||
226 | //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
|
||
227 | #endif
|
||
228 | } |
||
229 | |||
230 | //! shutdown and disable a joint
|
||
231 | //! \param the enum id of a joint
|
||
232 | void MekaJointInterface::disable_joint(int e){ |
||
233 | /*
|
||
234 | //first: convert humotion enum to our enum:
|
||
235 | int motor_id = convert_enum_to_motorid(e);
|
||
236 | if (motor_id == -1){
|
||
237 | return; //we are not interested in that data, so we just return here
|
||
238 | }
|
||
239 | |||
240 | //fetch device:
|
||
241 | Device *dev = get_device(motor_id);
|
||
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 | printf("> FIXME: ADD DISABLE CODE\n");
|
||
251 | */
|
||
252 | } |
||
253 | |||
254 | #if 0
|
||
255 | 2be6243f | Sebastian Meyer zu Borgsen | |
256 | //! conversion table for humotion motor ids to our ids:
|
||
257 | //! \param enum from JointInterface::JOINT_ID_ENUM
|
||
258 | //! \return int value of motor id
|
||
259 | int iCubJointInterface::convert_enum_to_motorid(int e){
|
||
260 | enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
|
||
261 | if(it == enum_id_bimap.right.end()) {
|
||
262 | //key does not exists, we are not interested in that dataset, return -1
|
||
263 | return -1;
|
||
264 | }
|
||
265 | return it->second;
|
||
266 | }
|
||
267 | |||
268 | |||
269 | //! conversion table for our ids to humotion motor ids:
|
||
270 | //! \param int value of motor id
|
||
271 | //! \return enum from JointInterface::JOINT_ID_ENUM
|
||
272 | int iCubJointInterface::convert_motorid_to_enum(int id){
|
||
273 | enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
|
||
274 | if(it == enum_id_bimap.left.end()) {
|
||
275 | //key does not exists, we are not interested in that dataset, return -1
|
||
276 | return -1;
|
||
277 | }
|
||
278 | return it->second;
|
||
279 | }
|
||
280 | |||
281 | //! special command to set eyelid angle
|
||
282 | //! \param angle in degrees
|
||
283 | void iCubJointInterface::set_eyelid_angle(double angle){
|
||
284 | if (emotion_port[0].getOutputCount()>0){
|
||
285 | //try to set the value based on the upper one
|
||
286 | //some guesses from the sim: S30 = 0° / S40 = 10°
|
||
287 | int opening = (25.0 + 0.8*angle);
|
||
288 | opening = min(48, max(24, opening));
|
||
289 | |||
290 | if (opening == lid_opening_previous){
|
||
291 | //no update necessary
|
||
292 | return;
|
||
293 | }
|
||
294 | |||
295 | lid_angle = angle;
|
||
296 | lid_opening_previous = opening;
|
||
297 | |||
298 | char buf[20];
|
||
299 | sprintf(buf, "S%2d", opening);
|
||
300 | |||
301 | //printf("> SETTING EYELID '%s' (%f -> %d)\n",buf,angle,opening);
|
||
302 | Bottle &cmd = emotion_port[0].prepare();
|
||
303 | cmd.clear();
|
||
304 | cmd.addString(buf);
|
||
305 | emotion_port[0].write();
|
||
306 | }else{
|
||
307 | printf("> ERROR: no icub emotion output\n");
|
||
308 | exit(EXIT_FAILURE);
|
||
309 | }
|
||
310 | }
|
||
311 | |||
312 | //! special command to set the eyebrow angle
|
||
313 | //! \param id {0=left, 1=right)
|
||
314 | //! \param angle in degrees
|
||
315 | void iCubJointInterface::set_eyebrow_angle(int id){
|
||
316 | int port_id;
|
||
317 | if (id == ICUB_ID_EYES_LEFT_BROW){
|
||
318 | port_id = 1;
|
||
319 | }else{
|
||
320 | port_id = 2;
|
||
321 | }
|
||
322 | |||
323 | if (emotion_port[port_id].getOutputCount()>0){
|
||
324 | double angle = target_angle[id];
|
||
325 | int icub_val = 0;
|
||
326 | |||
327 | //swap rotation direction:
|
||
328 | if (id==ICUB_ID_EYES_LEFT_BROW) angle = -angle;
|
||
329 | |||
330 | //convert to icub representation
|
||
331 | if (angle < -20){
|
||
332 | icub_val = 1;
|
||
333 | }else if (angle<10){
|
||
334 | icub_val = 2;
|
||
335 | }else if (angle<20){
|
||
336 | icub_val = 4;
|
||
337 | }else{
|
||
338 | icub_val = 8;
|
||
339 | }
|
||
340 | |||
341 | //make sure to update only on new values:
|
||
342 | if (icub_val == target_angle_previous[id]){
|
||
343 | //no updata necessary
|
||
344 | return;
|
||
345 | }
|
||
346 | |||
347 | //store actual value:
|
||
348 | target_angle_previous[id] = icub_val;
|
||
349 | |||
350 | |||
351 | string cmd_s;
|
||
352 | if (id==ICUB_ID_EYES_LEFT_BROW){
|
||
353 | cmd_s = "L0" + to_string(icub_val);
|
||
354 | }else{
|
||
355 | cmd_s = "R0" + to_string(icub_val);
|
||
356 | }
|
||
357 | |||
358 | printf("> SETTING EYEBROW %d (%f -> %s)\n",id,angle,cmd_s.c_str());
|
||
359 | |||
360 | Bottle &cmd = emotion_port[port_id].prepare();
|
||
361 | cmd.clear();
|
||
362 | cmd.addString(cmd_s);
|
||
363 | emotion_port[port_id].write();
|
||
364 | }else{
|
||
365 | printf("> ERROR: no icub emotion output\n");
|
||
366 | exit(EXIT_FAILURE);
|
||
367 | }
|
||
368 | }
|
||
369 | |||
370 | void iCubJointInterface::run(){
|
||
371 | iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
|
||
372 | data_receiver->start();
|
||
373 | }
|
||
374 | |||
375 | //! set the target position of a joint
|
||
376 | //! \param enum id of joint
|
||
377 | //! \param float value
|
||
378 | void iCubJointInterface::publish_target_position(int e){
|
||
379 | //first: convert humotion enum to our enum:
|
||
380 | int id = convert_enum_to_motorid(e);
|
||
381 | if (id == -1){
|
||
382 | return; //we are not interested in that data, so we just return here
|
||
383 | }
|
||
384 | |||
385 | if (id == ICUB_ID_NECK_PAN){
|
||
386 | //PAN seems to be swapped
|
||
387 | store_joint(ICUB_ID_NECK_PAN, -joint_target[e]);
|
||
388 | }else if ((id == ICUB_ID_EYES_LEFT_LR) || ( id == ICUB_ID_EYES_RIGHT_LR)){
|
||
389 | //icub handles eyes differently, we have to set pan angle + vergence
|
||
390 | float pan = (joint_target[ID_EYES_LEFT_LR] + joint_target[ID_EYES_RIGHT_LR]) / 2;
|
||
391 | float vergence = (joint_target[ID_EYES_LEFT_LR] - joint_target[ID_EYES_RIGHT_LR]);
|
||
392 | //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);
|
||
393 | |||
394 | store_joint(ICUB_ID_EYES_PAN, pan);
|
||
395 | store_joint(ICUB_ID_EYES_VERGENCE, vergence);
|
||
396 | }else{
|
||
397 | store_joint(id, joint_target[e]);
|
||
398 | }
|
||
399 | }
|
||
400 | |||
401 | |||
402 | //! set the target position of a joint
|
||
403 | //! \param id of joint
|
||
404 | //! \param float value of position
|
||
405 | void iCubJointInterface::store_joint(int id, float value){
|
||
406 | //printf("> set joint %d = %f\n",id,value);
|
||
407 | target_angle[id] = value;
|
||
408 | //ipos->positionMove(id, value);
|
||
409 | }
|
||
410 | |||
411 | //! execute a move in position mode
|
||
412 | //! \param id of joint
|
||
413 | //! \param angle
|
||
414 | void iCubJointInterface::set_target_in_positionmode(int id, double value){
|
||
415 | if (id>ICUB_ID_EYES_VERGENCE){
|
||
416 | printf("> ERROR: set_target_positionmode(id=%d, %3.2f) not supported for this id\n",id,value);
|
||
417 | return;
|
||
418 | }
|
||
419 | #if 0
|
||
420 | //set speed cacluated as in velocity + set position -> replicates smoothmotion from flobi?!
|
||
421 | |||
422 | //first: calculate necessary speed to reach the given target within the next clock tick:
|
||
423 | double distance = value - target_angle_previous[id];
|
||
424 | //make the motion smooth: we want to reach 85% of the target in the next iteration:
|
||
425 | //calculate speed for that:
|
||
426 | double speed = 0.85 * distance * ((double)MAIN_LOOP_FREQUENCY);
|
||
427 | |||
428 | //set up speed for controller:
|
||
429 | ipos->setRefSpeed(id, speed);
|
||
430 | #endif
|
||
431 | //execute motion
|
||
432 | ipos->positionMove(id, value); |
||
433 | } |
||
434 | |||
435 | //! execute a move in velocity mode
|
||
436 | //! \param id of joint
|
||
437 | //! \param angle
|
||
438 | void iCubJointInterface::set_target_in_velocitymode(int id, double value){ |
||
439 | //first: calculate necessary speed to reach the given target within the next clock tick:
|
||
440 | double distance = value - target_angle_previous[id];
|
||
441 | //make the motion smooth: we want to reach 85% of the target in the next iteration:
|
||
442 | distance = 0.85 * distance; |
||
443 | //calculate speed
|
||
444 | double speed = distance * ((double)MAIN_LOOP_FREQUENCY); |
||
445 | //execute:
|
||
446 | ivel->velocityMove(id, speed); |
||
447 | //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);
|
||
448 | |||
449 | target_angle_previous[id] = get_ts_position(convert_motorid_to_enum(id)).get_newest_value(); |
||
450 | } |
||
451 | |||
452 | //! actually execute the scheduled motion commands
|
||
453 | void iCubJointInterface::execute_motion(){
|
||
454 | |||
455 | // set up neck and eye motion commands:
|
||
456 | if (POSITION_CONTROL){
|
||
457 | //position control
|
||
458 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){ |
||
459 | set_target_in_positionmode(i, target_angle[i]); |
||
460 | } |
||
461 | }else{
|
||
462 | //velocity control
|
||
463 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){ |
||
464 | set_target_in_velocitymode(i, target_angle[i]); |
||
465 | } |
||
466 | } |
||
467 | //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
|
||
468 | |||
469 | |||
470 | //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
|
||
471 | set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]); |
||
472 | |||
473 | //eyebrows are set using a special command as well:
|
||
474 | set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW); |
||
475 | set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW); |
||
476 | |||
477 | //mouth
|
||
478 | set_mouth(); |
||
479 | |||
480 | |||
481 | } |
||
482 | |||
483 | void iCubJointInterface::set_mouth(){
|
||
484 | //convert from 6DOF mouth displacement to icub leds:
|
||
485 | int led_value = 0; |
||
486 | |||
487 | //fetch center opening:
|
||
488 | double center_opening = target_angle[ICUB_ID_LIP_CENTER_LOWER] - target_angle[ICUB_ID_LIP_CENTER_UPPER];
|
||
489 | bool mouth_open = (center_opening>15.0)?true:false; |
||
490 | |||
491 | //side of mouth high or low?
|
||
492 | double center_avg = (target_angle[ICUB_ID_LIP_CENTER_LOWER] + target_angle[ICUB_ID_LIP_CENTER_UPPER])/2.0; |
||
493 | double left_avg = (target_angle[ICUB_ID_LIP_LEFT_LOWER] + target_angle[ICUB_ID_LIP_LEFT_UPPER])/2.0; |
||
494 | double right_avg = (target_angle[ICUB_ID_LIP_RIGHT_LOWER] + target_angle[ICUB_ID_LIP_RIGHT_UPPER])/2.0; |
||
495 | |||
496 | //happy, neutral or sad?
|
||
497 | double diff_l = center_avg - left_avg;
|
||
498 | double diff_r = center_avg - right_avg;
|
||
499 | double diff = (diff_l+diff_r)/2.0; |
||
500 | |||
501 | if (diff > 2.0){ |
||
502 | if (mouth_open){
|
||
503 | led_value = 0x14;
|
||
504 | }else{
|
||
505 | if (diff > 2.6){ |
||
506 | led_value = 0x0A;
|
||
507 | }else{
|
||
508 | led_value = 0x0B;
|
||
509 | } |
||
510 | } |
||
511 | }else if (diff < -3.0){ |
||
512 | if (mouth_open){
|
||
513 | led_value = 0x06;
|
||
514 | }else{
|
||
515 | led_value = 0x18;
|
||
516 | } |
||
517 | }else if (diff < -2.0){ |
||
518 | if (mouth_open){
|
||
519 | led_value = 0x04; //0x25; |
||
520 | }else{
|
||
521 | led_value = 0x08;
|
||
522 | } |
||
523 | }else{
|
||
524 | if (mouth_open){
|
||
525 | led_value = 0x16;
|
||
526 | }else{
|
||
527 | led_value = 0x08;
|
||
528 | } |
||
529 | } |
||
530 | |||
531 | |||
532 | if (led_value == previous_mouth_state){
|
||
533 | //no update necessary
|
||
534 | return;
|
||
535 | } |
||
536 | |||
537 | previous_mouth_state = led_value; |
||
538 | |||
539 | //convert to string:
|
||
540 | char buf[10]; |
||
541 | sprintf(buf, "M%02X",led_value);
|
||
542 | |||
543 | /*printf("> sending mouth '%s'\n",buf);
|
||
544 | 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]);
|
||
545 | 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]);
|
||
546 | printf(" mouth open=%3.2f diff=%3.2f\n", center_opening, diff);*/
|
||
547 | |||
548 | //add mouth:
|
||
549 | Bottle &cmd = emotion_port[3].prepare();
|
||
550 | cmd.clear(); |
||
551 | cmd.addString(buf); |
||
552 | emotion_port[3].write();
|
||
553 | |||
554 | |||
555 | //store joint values which we do not handle on icub here:
|
||
556 | double timestamp = get_timestamp_ms();
|
||
557 | JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER, target_angle[ICUB_ID_LIP_LEFT_UPPER], timestamp); |
||
558 | JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER, target_angle[ICUB_ID_LIP_LEFT_LOWER], timestamp); |
||
559 | JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, target_angle[ICUB_ID_LIP_CENTER_UPPER], timestamp); |
||
560 | JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, target_angle[ICUB_ID_LIP_CENTER_LOWER], timestamp); |
||
561 | JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER, target_angle[ICUB_ID_LIP_RIGHT_UPPER], timestamp); |
||
562 | JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER, target_angle[ICUB_ID_LIP_RIGHT_LOWER], timestamp); |
||
563 | |||
564 | } |
||
565 | |||
566 | double iCubJointInterface::get_timestamp_ms(){
|
||
567 | struct timespec spec;
|
||
568 | clock_gettime(CLOCK_REALTIME, &spec); |
||
569 | return spec.tv_sec*1000 + spec.tv_nsec / 1.0e6; |
||
570 | } |
||
571 | |||
572 | //! set the current position of a joint
|
||
573 | //! \param id of joint
|
||
574 | //! \param float value of position
|
||
575 | //! \param double timestamp
|
||
576 | void iCubJointInterface::fetch_position(int id, double value, double timestamp){ |
||
577 | //store joint based on id:
|
||
578 | switch(id){
|
||
579 | default:
|
||
580 | printf("> ERROR: unhandled joint id %d\n",id);
|
||
581 | return;
|
||
582 | |||
583 | case(100): |
||
584 | JointInterface::store_incoming_position(ID_EYES_RIGHT_LID_UPPER, lid_angle, timestamp); |
||
585 | break;
|
||
586 | |||
587 | case(2): |
||
588 | //PAN is inverted!
|
||
589 | JointInterface::store_incoming_position(ID_NECK_PAN, -value, timestamp); |
||
590 | break;
|
||
591 | |||
592 | case(0): |
||
593 | JointInterface::store_incoming_position(ID_NECK_TILT, value, timestamp); |
||
594 | break;
|
||
595 | |||
596 | case(1): |
||
597 | JointInterface::store_incoming_position(ID_NECK_ROLL, value, timestamp); |
||
598 | break;
|
||
599 | |||
600 | case(3): |
||
601 | JointInterface::store_incoming_position(ID_EYES_BOTH_UD, value, timestamp); |
||
602 | break;
|
||
603 | |||
604 | //icub handles eyes differently, we have to set pan angle + vergence
|
||
605 | case(4): {//pan |
||
606 | last_pos_eye_pan = value; |
||
607 | float left = last_pos_eye_pan + last_pos_eye_vergence/2.0; |
||
608 | float right = last_pos_eye_pan - last_pos_eye_vergence/2.0; |
||
609 | |||
610 | //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);
|
||
611 | JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp); |
||
612 | JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp); |
||
613 | break;
|
||
614 | } |
||
615 | |||
616 | case(5): { //vergence |
||
617 | last_pos_eye_vergence = value; |
||
618 | float left = last_pos_eye_pan + last_pos_eye_vergence/2.0; |
||
619 | float right = last_pos_eye_pan - last_pos_eye_vergence/2.0; |
||
620 | |||
621 | //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);
|
||
622 | JointInterface::store_incoming_position(ID_EYES_LEFT_LR, left, timestamp); |
||
623 | JointInterface::store_incoming_position(ID_EYES_RIGHT_LR, right, timestamp); |
||
624 | break;
|
||
625 | } |
||
626 | } |
||
627 | |||
628 | |||
629 | } |
||
630 | |||
631 | //! set the current speed of a joint
|
||
632 | //! \param enum id of joint
|
||
633 | //! \param float value of speed
|
||
634 | //! \param double timestamp
|
||
635 | void iCubJointInterface::fetch_speed(int id, double value, double timestamp){ |
||
636 | |||
637 | switch(id){
|
||
638 | default:
|
||
639 | printf("> ERROR: unhandled joint id %d\n",id);
|
||
640 | return;
|
||
641 | |||
642 | case(2): |
||
643 | JointInterface::store_incoming_speed(ID_NECK_PAN, value, timestamp); |
||
644 | break;
|
||
645 | |||
646 | case(0): |
||
647 | JointInterface::store_incoming_speed(ID_NECK_TILT, value, timestamp); |
||
648 | break;
|
||
649 | |||
650 | case(1): |
||
651 | JointInterface::store_incoming_speed(ID_NECK_ROLL, value, timestamp); |
||
652 | break;
|
||
653 | |||
654 | case(3): |
||
655 | JointInterface::store_incoming_speed(ID_EYES_BOTH_UD, value, timestamp); |
||
656 | break;
|
||
657 | |||
658 | //icub handles eyes differently, we have to set pan angle + vergence
|
||
659 | case(4): {//pan |
||
660 | last_vel_eye_pan = value; |
||
661 | float left = last_vel_eye_pan + last_vel_eye_vergence/2.0; |
||
662 | float right = last_vel_eye_pan - last_vel_eye_vergence/2.0; |
||
663 | |||
664 | //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);
|
||
665 | JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp); |
||
666 | JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp); |
||
667 | break;
|
||
668 | } |
||
669 | |||
670 | case(5): { //vergence |
||
671 | last_vel_eye_pan = value; |
||
672 | float left = last_vel_eye_pan + last_vel_eye_vergence/2.0; |
||
673 | float right = last_vel_eye_pan - last_vel_eye_vergence/2.0; |
||
674 | |||
675 | //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);
|
||
676 | JointInterface::store_incoming_speed(ID_EYES_LEFT_LR, left, timestamp); |
||
677 | JointInterface::store_incoming_speed(ID_EYES_RIGHT_LR, right, timestamp); |
||
678 | break;
|
||
679 | } |
||
680 | } |
||
681 | /*
|
||
682 | JointInterface::store_incoming_speed(ID_LIP_LEFT_UPPER, 0.0, timestamp);
|
||
683 | JointInterface::store_incoming_speed(ID_LIP_LEFT_LOWER, 0.0, timestamp);
|
||
684 | JointInterface::store_incoming_speed(ID_LIP_CENTER_UPPER, 0.0, timestamp);
|
||
685 | JointInterface::store_incoming_speed(ID_LIP_CENTER_LOWER, 0.0, timestamp);
|
||
686 | JointInterface::store_incoming_speed(ID_LIP_RIGHT_UPPER, 0.0, timestamp);
|
||
687 | JointInterface::store_incoming_speed(ID_LIP_RIGHT_LOWER, 0.0, timestamp);
|
||
688 | |||
689 | JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_LOWER, 0.0, timestamp);
|
||
690 | JointInterface::store_incoming_speed(ID_EYES_LEFT_LID_UPPER, 0.0, timestamp);
|
||
691 | JointInterface::store_incoming_speed(ID_EYES_LEFT_BROW, 0.0, timestamp);
|
||
692 | |||
693 | JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_LOWER, 0.0, timestamp);
|
||
694 | JointInterface::store_incoming_speed(ID_EYES_RIGHT_LID_UPPER,0.0, timestamp);
|
||
695 | JointInterface::store_incoming_speed(ID_EYES_RIGHT_BROW, 0.0, timestamp);*/
|
||
696 | /*
|
||
697 | //fetch enum id:
|
||
698 | int e = convert_motorid_to_enum(device->get_device_id());
|
||
699 | if (e == -1){
|
||
700 | return; //we are not interested in that data, so we just return here
|
||
701 | }
|
||
702 | |||
703 | JointInterface::store_incoming_speed(e, device->get_register(XSC3_REGISTER_MOTORSPEED), timestamp);*/
|
||
704 | |||
705 | } |
||
706 | /*
|
||
707 | //! conversion table for humotion motor ids to our ids:
|
||
708 | //! \param enum from JointInterface::JOINT_ID_ENUM
|
||
709 | //! \return int value of motor id
|
||
710 | int HumotionJointInterface::convert_enum_to_motorid(int e){
|
||
711 | enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(e);
|
||
712 | if(it == enum_id_bimap.right.end()) {
|
||
713 | //key does not exists, we are not interested in that dataset, return -1
|
||
714 | return -1;
|
||
715 | }
|
||
716 | |||
717 | return it->second;
|
||
718 | }
|
||
719 | |||
720 | |||
721 | //! conversion table for our ids to humotion motor ids:
|
||
722 | //! \param int value of motor id
|
||
723 | //! \return enum from JointInterface::JOINT_ID_ENUM
|
||
724 | int HumotionJointInterface::convert_motorid_to_enum(int id){
|
||
725 | enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(id);
|
||
726 | if(it == enum_id_bimap.left.end()) {
|
||
727 | //key does not exists, we are not interested in that dataset, return -1
|
||
728 | return -1;
|
||
729 | }
|
||
730 | |||
731 | return it->second;
|
||
732 | }
|
||
733 | */
|
||
734 | |||
735 | //! prepare and enable a joint
|
||
736 | //! NOTE: this should also prefill the min/max positions for this joint
|
||
737 | //! \param the enum id of a joint
|
||
738 | void iCubJointInterface::enable_joint(int e){ |
||
739 | //FIXME ADD THIS:
|
||
740 | // enable the amplifier and the pid controller on each joint
|
||
741 | /*for (i = 0; i < nj; i++) {
|
||
742 | amp->enableAmp(i);
|
||
743 | pid->enablePid(i);
|
||
744 | }*/
|
||
745 | |||
746 | |||
747 | //set up smooth motion controller
|
||
748 | //step1: set up framerate
|
||
749 | //dev->set_register_blocking(XSC3_REGISTER_PID_RAMP, framerate, true);
|
||
750 | |||
751 | //step2: set controllertype:
|
||
752 | //printf("> activating smooth motion control for joint id 0x%02X (%s)\n", motor_id, joint_name.c_str());
|
||
753 | //dev->set_register_blocking(XSC3_REGISTER_PID_CONTROLLER, XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK, true);
|
||
754 | |||
755 | //step3: set pid controller:
|
||
756 | /*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)){
|
||
757 | printf("> fixing PID i controller value for smooth motion (FIXME: restore old value!!)\n");
|
||
758 | dev->set_register_blocking(XSC3_REGISTER_CONST_I, 10, true);
|
||
759 | }*/
|
||
760 | |||
761 | //uint16_t result = dev->get_register_blocking_raw(XSC3_REGISTER_PID_CONTROLLER);
|
||
762 | |||
763 | //check if setting pid controllertype was successfull:
|
||
764 | /*if (result != XSC3_PROTOCOL_PID_CONTROLLERTYPE_SMOOTH_PLAYBACK){
|
||
765 | printf("> failed to set smooth motion controller for joint %s (res=0x%04X)\n",joint_name.c_str(),result);
|
||
766 | exit(1);
|
||
767 | }*/
|
||
768 | |||
769 | //fetch min/max:
|
||
770 | // init_joint(e);
|
||
771 | |||
772 | //ok fine, now enable motor:
|
||
773 | //printf("> enabling motor %s\n", joint_name.c_str());
|
||
774 | //dev->set_register_blocking(XSC3_REGISTER_STATUS, XSC3_PROTOCOL_STATUS_BITMASK_MOTOR_ENABLE, true);
|
||
775 | |||
776 | } |
||
777 | |||
778 | void iCubJointInterface::store_min_max(IControlLimits *ilimits, int id, int e){ |
||
779 | double min, max;
|
||
780 | ilimits->getLimits(id, &min, &max); |
||
781 | joint_min[e] = min; |
||
782 | joint_max[e] = max; |
||
783 | } |
||
784 | |||
785 | //! initialise a joint (set up controller mode etc)
|
||
786 | //! \param joint enum
|
||
787 | void iCubJointInterface::init_joints(){
|
||
788 | store_min_max(ilimits, 0, ID_NECK_TILT);
|
||
789 | store_min_max(ilimits, 1, ID_NECK_ROLL);
|
||
790 | store_min_max(ilimits, 2, ID_NECK_PAN);
|
||
791 | store_min_max(ilimits, 3, ID_EYES_BOTH_UD);
|
||
792 | |||
793 | //icub handles eyes differently, we have to set pan angle + vergence
|
||
794 | double pan_min, pan_max, vergence_min, vergence_max;
|
||
795 | ilimits->getLimits(4, &pan_min, &pan_max);
|
||
796 | ilimits->getLimits(5, &vergence_min, &vergence_max);
|
||
797 | |||
798 | //this is not 100% correct, should be fixed:
|
||
799 | joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
|
||
800 | joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
|
||
801 | joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR]; |
||
802 | joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR]; |
||
803 | |||
804 | //eyelids:
|
||
805 | joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; //24-30; |
||
806 | joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; //48-30; |
||
807 | lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER]; |
||
808 | |||
809 | //eyebrows:
|
||
810 | joint_min[ID_EYES_LEFT_BROW] = -50;
|
||
811 | joint_max[ID_EYES_LEFT_BROW] = 50;
|
||
812 | joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW]; |
||
813 | joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW]; |
||
814 | |||
815 | //mouth:
|
||
816 | joint_min[ID_LIP_CENTER_UPPER] = 5;
|
||
817 | joint_max[ID_LIP_CENTER_UPPER] = 50;
|
||
818 | joint_min[ID_LIP_CENTER_LOWER] = 5;
|
||
819 | joint_max[ID_LIP_CENTER_LOWER] = 50;
|
||
820 | joint_min[ID_LIP_LEFT_UPPER] = 5;
|
||
821 | joint_max[ID_LIP_LEFT_UPPER] = 50;
|
||
822 | joint_min[ID_LIP_LEFT_LOWER] = 5;
|
||
823 | joint_max[ID_LIP_LEFT_LOWER] = 50;
|
||
824 | joint_min[ID_LIP_RIGHT_UPPER] = 5;
|
||
825 | joint_max[ID_LIP_RIGHT_UPPER] = 50;
|
||
826 | joint_min[ID_LIP_RIGHT_LOWER] = 5;
|
||
827 | joint_max[ID_LIP_RIGHT_LOWER] = 50;
|
||
828 | |||
829 | |||
830 | } |
||
831 | |||
832 | //! shutdown and disable a joint
|
||
833 | //! \param the enum id of a joint
|
||
834 | void iCubJointInterface::disable_joint(int e){ |
||
835 | /*
|
||
836 | //first: convert humotion enum to our enum:
|
||
837 | int motor_id = convert_enum_to_motorid(e);
|
||
838 | if (motor_id == -1){
|
||
839 | return; //we are not interested in that data, so we just return here
|
||
840 | }
|
||
841 | |||
842 | //fetch device:
|
||
843 | Device *dev = get_device(motor_id);
|
||
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 | printf("> FIXME: ADD DISABLE CODE\n");
|
||
853 | */
|
||
854 | } |
||
855 | 473a6a6c | Simon Schulz | #endif |