iCub-main
iCub_Sim.cpp
Go to the documentation of this file.
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 /*
4 * Copyright (C) 2010 RobotCub Consortium, European Commission FP6 Project IST-004370
5 * Author: Paul Fitzpatrick, Vadim Tikhanoff, Martin Peniak
6 * email: paulfitz@alum.mit.edu, vadim.tikhanoff@iit.it, martin.peniak@plymouth.ac.uk
7 * website: www.robotcub.org
8 * Permission is granted to copy, distribute, and/or modify this program
9 * under the terms of the GNU General Public License, version 2 or any
10 * later version published by the Free Software Foundation.
11 *
12 * A copy of the license can be found at
13 * http://www.robotcub.org/icub/license/gpl.txt
14 *
15 * This program is distributed in the hope that it will be useful, but
16 * WITHOUT ANY WARRANTY; without even the implied warranty of
17 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
18 * Public License for more details
19 */
20 
21 #include "iCub_Sim.h"
22 
23 #include "OdeInit.h"
24 #include <yarp/os/Log.h>
25 #include <yarp/os/LogStream.h>
26 #include <set>
27 
28 using namespace yarp::sig;
29 
30 // globals
31 Semaphore ODE_access(1);
32 #define CTRL_RAD2DEG (180.0/M_PI)
33 #define CTRL_DEG2RAD (M_PI/180.0)
34 
35 // locals
36 // NOTE that we use (long) instead of (clock_t), because on MacOS, (clock_t) is unsigned, while we need negative numbers
37 static long gl_frame_length = 1000/30; // update opengl and vision stream at 30 Hz
38 static long ode_step_length = 10; // target duration of the ODE step in CPU time (set to 0 to go as fast as possible, set to dstep*1000 to go realtime)
39 static double dstep = 10.0/1000.0; // step size in ODE's dWorldStep in seconds
40 
41 static bool glrun; // draw gl
42 static bool simrun; // run simulator thread
43 
44 static int stop = 0;
45 static int v = 0;
46 
47 static float xyz[3];
48 static float hpr[8];
49 static float rez[3];
50 
51 static int contactPoint;
52 static int mouseDiffx, mouseDiffy;
53 static bool picking = false;
54 static float cam_rx = 0.0, cam_ry = 0.0;
55 
56 static int width = 640;
57 static int height = 480;
58 
61 static int mouse_ray_x;
62 static int mouse_ray_y;
63 static float *VAD;
64 static float *VAD2;
65 const dReal *pos;
66 static float angle_xref = 0.0f;
67 static float angle_yref = 25.0f;
68 static float ydistance = 10.0f;
69 static float xdistance = 0.0f;
70 static float view_xyz[3]; // position x,y,z
71 static float view_hpr[3]; // heading, pitch, roll (degrees)
72 static float view2_xyz[3];
73 static float view2_hpr[3];
74 static float zoom = 0;
75 static float xpos = 0, ypos = 0, zpos = 0, xrot = 0, yrot = 0, zrot = 0, angle=0.0;
76 static float lastx, lasty;
77 static float xrotrad = 0, yrotrad = 0;
78 static long startTime, finishTime;
80 static float test[3];
81 //static SDL_TimerID id;
82 static Uint32 colorkey;
83 static SDL_Surface *image;
84 static bool extractImages = false;
85 static VideoTexture *video = NULL;
86 static RobotStreamer *robot_streamer = NULL;
87 static RobotConfig *robot_config = NULL;
88 static bool eyeCams;
89 static const GLfloat light_position[] = { 0.0f, 5.0f, 5.0f, 0.0f };
90 
91 //camera calibration parameters
92 static int width_left;
93 static int width_right;
94 static int height_left;
95 static int height_right;
96 static double fov_left;
97 static double fov_right;
98 
99 static int cameraSizeWidth;
100 static int cameraSizeHeight;
101 
105  std::set<unsigned int> taxelsTouched;
106 };
107 
108 static std::map<SkinPart,contactICubSkinEmul_t> contactICubSkinEmulMap;
109 
110 /* For every collision detected by ODE, contact joints (up to MAX_CONTACTS per collison) are created and a feedback structs may be associated with them - that will carry information about the contact.
111  * The number of collisions and contact joints may vary, but we allocate these as a static array for performance issues.
112  * (Allocating feedback structs at every simulation step would degrade simulation performance).
113  * If the MAX_DJOINT_FEEDBACKSTRUCTS was exceeded, contacts will still be saved for the purposes of whole_body_skin_emul,
114  * but the forces send to skinEvents will not be available.
115 */
116 #define MAX_DJOINT_FEEDBACKSTRUCTS 500
117 
119 static int nFeedbackStructs=0;
120 
121 static bool START_SELF_COLLISION_DETECTION = false; //we want to set this trigger on only after the robot is in in home pos -
122  //it's initial configuration is with arms inside the thighs
123 
124 
125 void OdeSdlSimulation::draw() {
126  OdeInit& odeinit = OdeInit::get();
127  odeinit._iCub->draw();
128  odeinit._wrld->draw();
129 }
130 
131 void OdeSdlSimulation::printStats() {
132  OdeInit& odeinit = OdeInit::get();
133 
134  finishTime = (long) clock() ;
135  duration += (double)(finishTime - startTime) / CLOCKS_PER_SEC ;
136  frames ++ ;
137  FPS = frames / duration ;
138  startTime = (long) clock() ;
139  odeinit.SimTime = duration;
140  //printf("duration: %.2lf\n",odeinit.SimTime);
141  static double starting_time_stamp = 0;
142  //test[0] = dBodyGetPosition(odeinit._iCub->body_cube[0])[0];
143  //test[1] = dBodyGetPosition(odeinit._iCub->body_cube[0])[1];
144  //test[2] = dBodyGetPosition(odeinit._iCub->body_cube[0])[2];
145  //printf("test[0] %f test[1] %f test[2] %f\n",test[0],test[1],test[2]);
146  if( duration - starting_time_stamp >= 1){
147  //printf("Frames: %.2lf Duration: %.2lf fps: %3.1f \n",frames,duration,FPS);
148  starting_time_stamp = duration;
149  }
150  //printf("%lf %lf %lf %lf %lf %lf\n", odeinit._iCub->ra_speed[0],odeinit._iCub->ra_speed[1],odeinit._iCub->ra_speed[2],odeinit._iCub->ra_speed[3],odeinit._iCub->ra_speed[4],odeinit._iCub->ra_speed[5]);
151  //drawText(text, textPos);
152 }
153 
154 void OdeSdlSimulation::handle_key_down(SDL_keysym* keysym) {
155  switch (keysym->sym)
156  {
157  case SDLK_e:
158  break;
159  case SDLK_r:
160  initViewpoint();
161  break;
162  case SDLK_t:
163  break;
164  case SDLK_y:
165  break;
166  case SDLK_SPACE:
167  printf("SPACEBAR pressed! Press spacebar again to disable/enable drawing.\n");
168  glrun = !glrun;
169  break;
170  default:
171  break;
172  }
173 }
174 
175 void OdeSdlSimulation::handle_mouse_motion(SDL_MouseMotionEvent* mousemotion) {
176  if (SDL_GetMouseState(NULL, NULL) & SDL_BUTTON(1)){// MOUSE LEFT BUTTON
177  //if (!picking){
178  //camera movement
179  angle_xref += (float)mousemotion->xrel; // 10.0f;
180  angle_yref += (float)mousemotion->yrel; // 10.0f;
181  mouseMovement(angle_xref,angle_yref);
182 
183  if (v<1){
184  //mouse_ray_x = mouse0_down_x;
185  //mouse_ray_y = mouse0_down_y;
186  }
187  /*mouseDiffx = mouse0_down_x - mouse_ray_x;
188  mouseDiffy = mouse0_down_y - mouse_ray_y;
189  mouse_ray_x = mouse0_down_x;
190  mouse_ray_y = mouse0_down_y;*/
191 
192  //VAD = ScreenToWorld(mouse0_down_x,mouse0_down_y,0);
193  //xpos = VAD[0];ypos = VAD[1];zpos = VAD[2];
194  //VAD2 =ScreenToWorld(mouse0_down_x,mouse0_down_y,1);
195  //xpos2 = VAD2[0];ypos2 = VAD2[1];zpos2 = VAD2[2];
196 
197  //if (i<1){ray = dCreateRay(space,100*100);}
198  //Origin[0] = xpos;
199  //Origin[1] = ypos;
200  //Origin[2] = zpos;
201  //Origin[3] = 0;
202  //Direction[0] = xpos2;
203  //Direction[1] = ypos2;
204  //Direction[2] = zpos2;
205  //Direction[3] = 0;
206  //dGeomRaySet(ray, Origin[0], Origin[1], Origin[2], Direction[0], Direction[1], Direction[2]);
207  //dGeomSetPosition(ray, xpos,ypos,zpos);
208  //i++;
209  }
210  if (SDL_GetMouseState(NULL, NULL) & SDL_BUTTON(3)){// MOUSE RIGHT BUTTON
211 
212  //xdistance -= mousemotion->xrel / 10.0f;
213  //ydistance -= mousemotion->yrel / 10.0f;
214  }
215 }
216 
217 void OdeSdlSimulation::process_events(void) {
218  OdeInit& odeinit = OdeInit::get();
219  SDL_Event event;
220 
221  Uint8 * keystate = SDL_GetKeyState(NULL);
222  if(keystate[SDLK_q]){xrot += 1 * 0.4f;if (xrot >360) xrot -= 360 * 0.1f;}
223  if(keystate[SDLK_z]){xrot -= 1 * 0.4f;if (xrot < -360) xrot += 360 * 0.1f;}
224  if(keystate[SDLK_w]){yrotrad = (yrot / 180 * 3.141592654f); xrotrad = (xrot / 180 * 3.141592654f);
225  xpos += float(sin(yrotrad))* 0.005f; ;zpos -= float(cos(yrotrad))* 0.005f; ypos -= float(sin(xrotrad))* 0.005f;}
226  if(keystate[SDLK_s]){yrotrad = (yrot / 180 * 3.141592654f); xrotrad = (xrot / 180 * 3.141592654f);
227  xpos -= float(sin(yrotrad))* 0.005f;zpos += float(cos(yrotrad))* 0.005f; ;ypos += float(sin(xrotrad))* 0.005f;}
228  if (keystate[SDLK_a]){yrotrad = (yrot / 180 * 3.141592654f);xpos -= float(cos(yrotrad)) * 0.008;zpos -= float(sin(yrotrad)) * 0.008; }
229  if (keystate[SDLK_d]){yrotrad = (yrot / 180 * 3.141592654f);xpos += float(cos(yrotrad)) * 0.008;zpos += float(sin(yrotrad)) * 0.008;}
230  if(keystate[SDLK_e]){zrot += 1 * 0.4f;if (zrot >360) zrot -= 360 * 0.4f;}
231  if(keystate[SDLK_c]){zrot -= 1 * 0.4f;if (zrot < -360) zrot += 360 * 0.4f;}
232 
233  if (keystate[SDLK_f]){ypos +=1 *0.005f;}
234  if (keystate[SDLK_v]){ypos -=1 *0.005f;}
235 
236  if(keystate[SDLK_1]){initViewpoint();}
237 
238  if (keystate[SDLK_5]){
239 
240  if ((odeinit._iCub->eyeLidRot) < 0.55) odeinit._iCub->eyeLidRot += 0.01;
241  cout<<odeinit._iCub->eyeLidRot<<endl;
242  }
243  if (keystate[SDLK_6]){
244  if ((odeinit._iCub->eyeLidRot) > 0.01) odeinit._iCub->eyeLidRot -= 0.01;
245  cout<<odeinit._iCub->eyeLidRot<<endl;
246  }
247  if (keystate[SDLK_h])
248  {
249  odeinit.sendHomePos();
250  }
251  /* Grab all the events off the queue. */
252  while (SDL_PollEvent(&event)){
253  switch (event.type)
254  {
255  case SDL_VIDEORESIZE:
256  width = event.resize.w;
257  height = event.resize.h;
258  SDL_SetVideoMode(width,height,16,SDL_OPENGL | SDL_RESIZABLE);
259  {
260  bool ok = setup_opengl(robot_config->getFinder());
261  if (!ok) {
262  odeinit.stop = true;
263  }
264  }
265  odeinit._iCub->reinitialized = true;
266  //draw_screen( );
267  break;
268  case SDL_KEYDOWN:
269  /* Handle key presses*/
270  handle_key_down(&event.key.keysym);
271  // SDL_GetKeyName(event.key.keysym.sym));
272  break;
273  break;
274  case SDL_MOUSEMOTION:
275  handle_mouse_motion(&event.motion);
276  mouse0_down_x = event.button.x;
277  mouse0_down_y = event.button.y;
278  break;
279  case SDL_QUIT:
280  /* Handle quit requests (like Ctrl-c). */
281  odeinit.stop = true;
282  break;
283 
284  case SDL_MOUSEBUTTONDOWN:
285  handle_mouse_motion(&event.motion);
286  switch (event.button.button)
287  {
288  case SDL_BUTTON_LEFT:
289  //deleteRay = false;
290  picking = false;
291  //printf(" Down\n");
292  break;
293  case SDL_BUTTON_MIDDLE:
294  break;
295  case SDL_BUTTON_RIGHT:
296  break;
297  default:
298  //this is not reached
299  break;
300  }
301  break;
302  break;
303  case SDL_MOUSEBUTTONUP:
304  switch (event.button.button)
305  {
306  case SDL_BUTTON_LEFT:
307  //printf(" up\n");
308  v=0;
309  break;
310  case SDL_BUTTON_MIDDLE:
311  //nothing
312  break;
313  case SDL_BUTTON_RIGHT:
314  //nothing
315  break;
316  default:
317  //this is not reached either
318  break;
319  }
320  break;
321  }
322  }
323 }
324 
325 void OdeSdlSimulation::nearCallback (void *data, dGeomID o1, dGeomID o2) {
326 
327  const double CONTACT_HEIGHT_TRESHOLD_METERS = 0.1; //for debugging or skin emulation purposes, assuming the robot is in contact with a flat ground (typically standing),
328  //the contacts generated between the robot and the ground that are always present can be ignored
329 
330  OdeInit& odeinit = OdeInit::get();
331 
332  assert(o1);
333  assert(o2);
334 
335  dSpaceID space1,space2;
336  dSpaceID superSpace1,superSpace2;
337  std::string geom1className("");
338  std::string geom2ClassName("");
339  std::string geom1name("");
340  std::string geom2name("");
341  bool geom1isiCubPart = false;
342  bool geom2isiCubPart = false;
343  bool geom1isTorsoOrArm = false;
344  bool geom2isTorsoOrArm = false;
345  int subLevel1;
346  //determine the indentation level for the printouts based on the sublevel in the hiearchy of spaces
347  string indentString("");
348  std::map<dGeomID,string>::iterator geom1namesIt;
349  std::map<dGeomID,string>::iterator geom2namesIt;
350 
351  if (dGeomIsSpace(o1)){
352  space1 = (dSpaceID)o1;
353  } else {
354  space1 = dGeomGetSpace(o1);
355  indentString = indentString + " --- "; //extra indentation level because it is a geom in that space
356  }
357  subLevel1 = dSpaceGetSublevel(space1);
358  for (int i=1;i<=subLevel1;i++){ //start from i=1, for sublevel==0 we don't add any indentation
359  indentString = indentString + " --- ";
360  }
361 
362  if (odeinit.verbosity > 3) printf("%s nearCallback()\n",indentString.c_str());
363 
364  if (dGeomIsSpace(o1)){
365  space1 = (dSpaceID)o1;
366  if (odeinit.verbosity > 3){
367  printf("%s Object nr. 1: %s, sublevel: %d, contained within: %s, nr. geoms: %d. \n",indentString.c_str(),odeinit._iCub->dSpaceNames[space1].c_str(),dSpaceGetSublevel(space1),odeinit._iCub->dSpaceNames[dGeomGetSpace(o1)].c_str(),dSpaceGetNumGeoms(space1));
368  }
369  }
370  else{ //it's a geom
371  getGeomClassName(dGeomGetClass(o1),geom1className);
372  superSpace1 = dGeomGetSpace(o1);
373  geom1namesIt = odeinit._iCub->dGeomNames.find(o1);
374  if (geom1namesIt != odeinit._iCub->dGeomNames.end()){
375  geom1name = geom1namesIt->second;
376  if (odeinit.verbosity > 3) printf("%s Object nr. 1: geom: %s, class: %s, contained within %s (sublevel %d).\n",indentString.c_str(),geom1name.c_str(),geom1className.c_str(),odeinit._iCub->dSpaceNames[superSpace1].c_str(),dSpaceGetSublevel(superSpace1));
377  }
378  else{
379  if (odeinit.verbosity > 3) printf("%s Object nr. 1: A geom, ID: %p, class: %s, contained within %s (sublevel %d).\n",indentString.c_str(),o1,geom1className.c_str(),odeinit._iCub->dSpaceNames[superSpace1].c_str(),dSpaceGetSublevel(superSpace1));
380  }
381  }
382 
383  if (dGeomIsSpace(o2)){
384  space2 = (dSpaceID)o2;
385  if (odeinit.verbosity > 3){
386  printf("%s Object nr. 2: %s, sublevel: %d, contained within: %s, nr. geoms: %d. \n",indentString.c_str(),odeinit._iCub->dSpaceNames[space2].c_str(),dSpaceGetSublevel(space2),odeinit._iCub->dSpaceNames[dGeomGetSpace(o2)].c_str(),dSpaceGetNumGeoms(space2));
387  }
388  } else {
389  getGeomClassName(dGeomGetClass(o2),geom2ClassName);
390  superSpace2 = dGeomGetSpace(o2);
391  geom2namesIt = odeinit._iCub->dGeomNames.find(o2);
392  if (geom2namesIt != odeinit._iCub->dGeomNames.end()){
393  geom2name = geom2namesIt->second;
394  if (odeinit.verbosity > 3) printf("%s Object nr. 2: geom: %s, class: %s, contained within %s (sublevel %d).\n",indentString.c_str(),geom2name.c_str(),geom2ClassName.c_str(),odeinit._iCub->dSpaceNames[superSpace2].c_str(),dSpaceGetSublevel(superSpace2));
395  }
396  else{
397  if (odeinit.verbosity > 3) printf("%s Object nr. 2: A geom, ID: %p, class: %s, contained within %s (sublevel %d).\n",indentString.c_str(),o2,geom2ClassName.c_str(),odeinit._iCub->dSpaceNames[superSpace2].c_str(),dSpaceGetSublevel(superSpace2));
398  }
399  }
400 
401  // if at least one of the geoms is a space, we need to go deeper -> recursive calls
402  if (dGeomIsSpace(o1) || dGeomIsSpace(o2)){
403  if (dGeomIsSpace(o1) && dGeomIsSpace(o2)){ //if both are spaces, we exclude special combinations from the checking
404  if (((space1 == odeinit._iCub->iCubHeadSpace) && (space2 == odeinit._iCub->iCubTorsoSpace)) || ((space1 == odeinit._iCub->iCubTorsoSpace) && (space2 == odeinit._iCub->iCubHeadSpace))){
405  if (odeinit.verbosity > 3) printf("%s Ignoring head vs. torso collision space checking.\n",indentString.c_str());
406  //these are unnecessary geoms to check, moreover 2 of these were colliding while not connected by a joint
407  }
408  else if (((space1 == odeinit._iCub->iCubLegsSpace) && (space2 == odeinit._iCub->iCubTorsoSpace)) || ((space1 == odeinit._iCub->iCubTorsoSpace) && (space2 == odeinit._iCub->iCubLegsSpace))){
409  if (odeinit.verbosity > 3) printf("%s Ignoring legs vs. torso collision space checking.\n",indentString.c_str());
410  //these are unnecessary geoms to check - it always check collisions of geoms connected by a joint
411  }
412  else{
413  dSpaceCollide2(o1,o2,data,&nearCallback);
414  }
415  }
416  else{
417  dSpaceCollide2(o1,o2,data,&nearCallback);
418  }
419  //}
420  //if (dGeomIsSpace(o2)){
421  // dSpaceCollide2(o2,o1,data,&nearCallback); //start the recursion from the other end
422  //}
423  return;
424  }
425  /* Note we do not want to test intersections within a space,
426  * only between spaces. Therefore, we do not call dSpaceCollide ((dSpaceID)o1, data, &nearCallback) and the same for o2 */
427 
428  /* if we made it up to here, it means we have two geoms (not spaces) o1, o2 from two different spaces and we should handle their collision */
429 
430  dBodyID b1 = dGeomGetBody(o1);
431  dBodyID b2 = dGeomGetBody(o2);
432  if (b1 && b2 && dAreConnectedExcluding (b1,b2,dJointTypeContact)){
433  if (odeinit.verbosity > 3) printf("%s Collision ignored: the bodies of o1 and o2 are connected by a joint.\n",indentString.c_str());
434  return;
435  }
436  // list of self-collisions to ignore
437  if (selfCollisionOnIgnoreList(geom1name,geom2name)){
438  if (odeinit.verbosity > 3){
439  printf("%s geom: %s (class: %s, contained within %s) AND geom: %s (class: %s, contained within %s).\n",indentString.c_str(),geom1name.c_str(),geom1className.c_str(),odeinit._iCub->dSpaceNames[superSpace1].c_str(),geom2name.c_str(),geom2ClassName.c_str(),odeinit._iCub->dSpaceNames[superSpace2].c_str());
440  printf("%s Collision ignored (ignore list).\n",indentString.c_str());
441  }
442  return;
443  }
444 
445  if (odeinit.verbosity > 3) printf("%s Collision candidate. Preparing contact joints.\n",indentString.c_str());
446  dContact contact[MAX_CONTACTS]; // up to MAX_CONTACTS contacts per box-box
447  int i;
448  for (i=0; i<MAX_CONTACTS; i++) {
449  contact[i].surface.mode = dContactSlip1| dContactSlip2| dContactBounce | dContactSoftCFM;
450  contact[i].surface.mu = dInfinity;
451  contact[i].surface.mu2 = 0;
452  contact[i].surface.bounce = 0.01;
453  contact[i].surface.bounce_vel = 0.01;
454  contact[i].surface.slip1 = (dReal)0.000001;
455  contact[i].surface.slip2 = (dReal)0.000001;
456  contact[i].surface.soft_cfm = 0.0001;
457  }
458  int numc = dCollide (o1,o2,MAX_CONTACTS,&contact[0].geom,sizeof(dContact));
459  if (numc > 0){
460  if (odeinit.verbosity > 3) printf("%s Collision suspect confirmed. There are %d contacts - creating joints.\n",indentString.c_str(),numc);
461  dMatrix3 RI;
462  dRSetIdentity (RI);
463  if(contact[0].geom.pos[1]>CONTACT_HEIGHT_TRESHOLD_METERS){ //non-foot contact
464  if (odeinit.verbosity > 2){
465  printf("%s ****** non-ground COLLISION, %d contacts - creating joints************************************************************\n",indentString.c_str(),numc);
466  printf("%s geom: %s (%s, contained within %s) AND geom: %s (%s, contained within %s)\n",indentString.c_str(),geom1name.c_str(),geom1className.c_str(),odeinit._iCub->dSpaceNames[superSpace1].c_str(),geom2name.c_str(),geom2ClassName.c_str(),odeinit._iCub->dSpaceNames[superSpace2].c_str());
467  }
468  }
469  for (i=0; i<numc; i++) {
470  if (odeinit.verbosity > 4) printf("%s Contact joint nr. %d (index:%d): at (%f,%f,%f), depth: %f \n",indentString.c_str(),i+1,i,contact[i].geom.pos[0],contact[i].geom.pos[1],contact[i].geom.pos[2],contact[i].geom.depth);
471  dJointID c = dJointCreateContact (odeinit.world,odeinit.contactgroup,contact+i);
472  dJointAttach (c,b1,b2);
473  // if (show_contacts) dsDrawBox (contact[i].geom.pos,RI,ss);
474  // check if the bodies are touch sensitive.
475  if (odeinit._iCub->actSkinEmul == "off"){ //this is the old implementation - hands (fingers and palm) are checked for touch
476  bool b1isTouchSensitive = isBodyTouchSensitive (b1);
477  bool b2isTouchSensitive = isBodyTouchSensitive (b2);
478  // if any of the bodies are touch sensitive...
479  if (b1isTouchSensitive || b2isTouchSensitive) {
480  // ... add a feedback structure to the contact joint.
481  if (odeinit.verbosity > 2) printf("%s Adding tactile feedback for emulating finger/palm skin to this one (ODE joint feedback counter: %d).\n",indentString.c_str(),nFeedbackStructs);
482  dJointSetFeedback (c, &(touchSensorFeedbacks[nFeedbackStructs]));
484  }
485  }
486  else { //whole_body_skin_emul ~ actSkinEmul is on
487  /* here we treat all bodies belonging to the icub as touch sensitive
488  * we want to know if the geom is part of the iCub - that is its superSpace is one of the iCub subspaces*/
489 
490  if ((superSpace1 == odeinit._iCub->iCubHeadSpace) || (superSpace1 == odeinit._iCub->iCubLegsSpace)){
491  geom1isiCubPart = true;
492  }
493  else if ((superSpace1==odeinit._iCub->iCubTorsoSpace) || (superSpace1==odeinit._iCub->iCubLeftArmSpace) || (superSpace1== odeinit._iCub->iCubRightArmSpace)){
494  geom1isiCubPart = true;
495  geom1isTorsoOrArm = true;
496  }
497  // || (superSpace1 == iCub){ - this should never happen here - in the self-collision mode, the iCub space contains only subspaces - no geoms directly
498 
499  if ((superSpace2 == odeinit._iCub->iCubHeadSpace) || (superSpace2 == odeinit._iCub->iCubLegsSpace)){
500  geom2isiCubPart = true;
501  }
502  else if ((superSpace2==odeinit._iCub->iCubTorsoSpace) || (superSpace2==odeinit._iCub->iCubLeftArmSpace) || (superSpace2== odeinit._iCub->iCubRightArmSpace)){
503  geom2isiCubPart = true;
504  geom2isTorsoOrArm = true;
505  }
506 
507  // if (geom1isiCubPart || geom2isiCubPart){ //we don't have the legs and head implemented yet - these don't have skin in the real robot - but legs will -> should do that
508  if ( geom1isTorsoOrArm || geom2isTorsoOrArm){
509  if (odeinit.verbosity > 3) printf("%s Adding tactile feedback for whole-body skinContact to this contact (ODE joint feedback counter: %d).\n",indentString.c_str(),nFeedbackStructs);
511  printf("Warning: out of contact joint feedback structures for ODE (exceeded %d) - some contact joints will not have info about forces stored\n.",MAX_DJOINT_FEEDBACKSTRUCTS);
512  }
513  else{
514  dJointSetFeedback (c, &(touchSensorFeedbacks[nFeedbackStructs]));
515  nFeedbackStructs++;
516  }
517  OdeInit::contactOnSkin_t contactOnSkin, contactOnSkin2;
518  if (geom1isiCubPart){
519  contactOnSkin.body_geom_space_id = superSpace1;
520  contactOnSkin.body_geom_id = o1;
521  contactOnSkin.body_index = 1;
522  contactOnSkin.contact_geom = contact[i].geom;
523  contactOnSkin.contact_joint = c;
524  odeinit.listOfSkinContactInfos.push_back(contactOnSkin);
525  }
526  if (geom2isiCubPart){
527  contactOnSkin2.body_geom_space_id = superSpace2;
528  contactOnSkin2.body_geom_id = o2;
529  contactOnSkin2.body_index = 2;
530  contactOnSkin2.contact_geom = contact[i].geom;
531  contactOnSkin2.contact_joint = c;
532  odeinit.listOfSkinContactInfos.push_back(contactOnSkin2);
533  }
534  }
535  else {
536  if (odeinit.verbosity > 3) printf("%s Ignoring skin contact - so far only arms and torso are implemented.\n",indentString.c_str());
537  }
538  } //whole_body_skin_emul ~ actSkinEmul is on
539  if (odeinit.verbosity > 3) printf("\n");
540  } // for numc - contacts
541  } // if (numc > 0)
542  else{
543  if (odeinit.verbosity > 3) printf("%s Collision suspect NOT confirmed. There were %d contacts.\n",indentString.c_str(),numc);
544  }
545 }
546 
547 
548 bool OdeSdlSimulation::selfCollisionOnIgnoreList(string geom1_string, string geom2_string)
549 {
551  if ( ( (geom1_string.compare("upper left arm cover")==0) && (geom2_string.compare("torsoGeom[4]")==0) ) || ( (geom2_string.compare("upper left arm cover")==0) && (geom1_string.compare("torsoGeom[4]")==0) ) ){
552  return true;
553  }
554  if ( ( (geom1_string.compare("upper left arm cover")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("upper left arm cover")==0) && (geom1_string.compare("torso cover")==0) ) ){
555  return true;
556  }
557  if ( ( (geom1_string.compare("geom[2]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[2]")==0) && (geom1_string.compare("torso cover")==0) ) ){
558  return true;
559  } //geom[2] is the cylinder in at shoulder joint (when it is "on" - part activated, it may collide ; when off (different geom name), it will not go into the torso, so no need to handle this)
560 
561  if ( ( (geom1_string.compare("geom[4]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[4]")==0) && (geom1_string.compare("torso cover")==0) ) ){
562  return true;
563  } //geom[4] is the cylinder in upper left arm (similarly, no need to test for the version with part off (ICubSim::initLeftArmOff))
564  if ( ( (geom1_string.compare("geom[4]")==0) && (geom2_string.compare("torsoGeom[5]")==0) ) || ( (geom2_string.compare("geom[4]")==0) && (geom1_string.compare("torsoGeom[5]")==0) ) ){
565  return true;
566  } //upper arm cylinder colliding with torso box
567 
569  if ( ( (geom1_string.compare("upper right arm cover")==0) && (geom2_string.compare("torsoGeom[5]")==0) ) || ( (geom2_string.compare("upper right arm cover")==0) && (geom1_string.compare("torsoGeom[5]")==0) ) ){
570  return true;
571  }
572  if ( ( (geom1_string.compare("upper right arm cover")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("upper right arm cover")==0) && (geom1_string.compare("torso cover")==0) ) ){
573  return true;
574  }
575  if ( ( (geom1_string.compare("geom[3]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[3]")==0) && (geom1_string.compare("torso cover")==0) ) ){
576  return true;
577  } //geom[3] is the cylinder in at shoulder joint (when it is "on" - part activated, it may collide ; when off (different geom name), it will not go into the torso, so no need to handle this)
578  if ( ( (geom1_string.compare("geom[5]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[5]")==0) && (geom1_string.compare("torso cover")==0) ) ){
579  return true;
580  } //geom[5] is the cylinder in upper right arm (similarly, no need to test for the version with part off (ICubSim::initRightArmOff))
581  if ( ( (geom1_string.compare("geom[5]")==0) && (geom2_string.compare("torsoGeom[5]")==0) ) || ( (geom2_string.compare("geom[5]")==0) && (geom1_string.compare("torsoGeom[5]")==0) ) ){
582  return true;
583  } //upper arm cylinder colliding with torso box
584 
586  if ( ( (geom1_string.compare("upper left arm cover")==0) && (geom2_string.compare("torsoGeom[4]")==0) ) || ( (geom2_string.compare("upper left arm cover")==0) && (geom1_string.compare("torsoGeom[4]")==0) ) ){
587  return true;
588  }
589  if ( ( (geom1_string.compare("upper left arm cover")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("upper left arm cover")==0) && (geom1_string.compare("torso cover")==0) ) ){
590  return true;
591  }
592  if ( ( (geom1_string.compare("geom[2]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[2]")==0) && (geom1_string.compare("torso cover")==0) ) ){
593  return true;
594  } //geom[2] is the cylinder in at shoulder joint (when it is "on" - part activated, it may collide ; when off (different geom name), it will not go into the torso, so no need to handle this)
595 
596  if ( ( (geom1_string.compare("geom[4]")==0) && (geom2_string.compare("torso cover")==0) ) || ( (geom2_string.compare("geom[4]")==0) && (geom1_string.compare("torso cover")==0) ) ){
597  return true;
598  } //geom[4] is the cylinder in upper left arm (similarly, no need to test for the version with part off (ICubSim::initLeftArmOff))
599  if ( ( (geom1_string.compare("geom[4]")==0) && (geom2_string.compare("torsoGeom[5]")==0) ) || ( (geom2_string.compare("geom[4]")==0) && (geom1_string.compare("torsoGeom[5]")==0) ) ){
600  return true;
601  } //upper arm cylinder colliding with torso box
602 
603 
604  return false;
605 }
606 
607 // returns true if the body with the bodyID is a touch-sensitive body, returns false otherwise.
608 bool OdeSdlSimulation::isBodyTouchSensitive (dBodyID bodyID) {
609  OdeInit& odeinit = OdeInit::get();
610 
611  // check the smaller hand parts if the left hand is active.
612  if (odeinit._iCub->actLHand == "on") {
613  if (bodyID == odeinit._iCub->body[10]) {
614  return true;
615  } else if (bodyID == odeinit._iCub->body[30]) {
616  return true;
617  } else if (bodyID == odeinit._iCub->body[24]) {
618  return true;
619  } else if (bodyID == odeinit._iCub->body[25]) {
620  return true;
621  } else if (bodyID == odeinit._iCub->lhandfingers3) {
622  return true;
623  }
624  } else { // check the whole left hand body if the hand is not active.
625  if (bodyID == odeinit._iCub->l_hand) {
626  return true;
627  }
628  }
629 
630  // check the smaller hand parts if the right hand is active.
631  if (odeinit._iCub->actRHand == "on") {
632  if (bodyID == odeinit._iCub->body[11]) {
633  return true;
634  } else if (bodyID == odeinit._iCub->body[49]) {
635  return true;
636  } else if (bodyID == odeinit._iCub->body[43]) {
637  return true;
638  } else if (bodyID == odeinit._iCub->body[44]) {
639  return true;
640  } else if (bodyID == odeinit._iCub->rhandfingers3) {
641  return true;
642  }
643  } else { // check the whole right hand body if the hand is not active.
644  if (bodyID == odeinit._iCub->r_hand) {
645  return true;
646  }
647  }
648 
649  return false;
650 }
651 
652 // this is a function to mimic the sensor data from the physical icub fingertip/palm sensors
653 //but the palm cover is not being checked here
654 void OdeSdlSimulation::inspectHandTouch_icubSensors(Bottle& reportLeft, Bottle& reportRight, bool boolean) {
655  OdeInit& odeinit = OdeInit::get();
656  reportLeft.clear();
657  reportRight.clear();
658  int indicesLeft[6] = {24, 25, 26, 27, 30, 10};
659  int indicesRight[6] = {43, 44, 45, 46, 49, 11};
660 
661  if (odeinit._iCub->actLHand == "on" && odeinit._iCub->actRHand == "on" ){
662  double resultLeft=0, resultRight = 0;
663  for (int x = 0; x < 6; x++){
664  if (boolean){
665  resultLeft = odeinit._iCub->checkTouchSensor( indicesLeft[x] );
666  resultRight = odeinit._iCub->checkTouchSensor( indicesRight[x] );
667  }
668  else{
669  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( indicesLeft[x] );
670  resultRight = odeinit._iCub->checkTouchSensor_continuousValued( indicesRight[x] );
671  }
672 
673  if (x < 5){ //five fingers
674  for (int i = 0; i < 12; i++){
675  reportLeft.addDouble(resultLeft * 255);
676  reportRight.addDouble(resultRight * 255);
677  }
678  }
679  if (x == 5){
680  for (int y = 0; y<3; y++){
681  for (int i = 0; i < 12; i++){
682  reportLeft.addDouble(0.0);
683  reportRight.addDouble(0.0);
684  }
685  }
686  //these are palm taxels
687  for (int y = 0; y<4; y++){
688  for (int i = 0; i < 12; i++){
689  reportLeft.addDouble(resultLeft * 255);
690  reportRight.addDouble(resultRight * 255);
691  }
692  }
693  for (int y = 0; y<4; y++){
694  for (int i = 0; i < 12; i++){
695  reportLeft.addDouble(0.0);
696  reportRight.addDouble(0.0);
697  }
698  }
699  }
700  }
701  }//end lhand on rhand on
702  else if (odeinit._iCub->actLHand == "on" && odeinit._iCub->actRHand == "off" ){
703  double resultLeft=0, resultRight = 0;
704  for (int x = 0; x < 6; x++){
705  if (boolean){
706  resultLeft = odeinit._iCub->checkTouchSensor( indicesLeft[x] );
707  resultRight = odeinit._iCub->checkTouchSensor( odeinit._iCub->r_hand );
708  }
709  else{
710  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( indicesLeft[x] );
711  resultRight = odeinit._iCub->checkTouchSensor_continuousValued(odeinit._iCub->r_hand);
712  }
713  if (x < 5){
714  for (int i = 0; i < 12; i++){
715  reportLeft.addDouble(resultLeft * 255);
716  reportRight.addDouble(resultRight * 255);
717  }
718  }
719  if (x == 5){
720  for (int y = 0; y<3; y++){
721  for (int i = 0; i < 12; i++){
722  reportLeft.addDouble(0.0);
723  reportRight.addDouble(0.0);
724  }
725  }
726  for (int y = 0; y<4; y++){
727  for (int i = 0; i < 12; i++){
728  reportLeft.addDouble(resultLeft * 255);
729  reportRight.addDouble(resultRight * 255);
730  }
731  }
732  for (int y = 0; y<4; y++){
733  for (int i = 0; i < 12; i++){
734  reportLeft.addDouble(0.0);
735  reportRight.addDouble(0.0);
736  }
737  }
738  }
739  }
740  }//end lhand on rhand off
741  else if (odeinit._iCub->actRHand == "on" && odeinit._iCub->actLHand == "off" ){
742  double resultLeft=0, resultRight = 0;
743  for (int x = 0; x < 6; x++){
744  if (boolean){
745  resultLeft = odeinit._iCub->checkTouchSensor( odeinit._iCub->l_hand );
746  resultRight = odeinit._iCub->checkTouchSensor( indicesRight[x] );
747  }
748  else{
749  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( odeinit._iCub->l_hand );
750  resultRight = odeinit._iCub->checkTouchSensor_continuousValued( indicesRight[x] );
751  }
752 
753  if (x < 5){
754  for (int i = 0; i < 12; i++){
755  reportLeft.addDouble(resultLeft * 255);
756  reportRight.addDouble(resultRight * 255);
757  }
758  }
759  if (x == 5){
760  for (int y = 0; y<3; y++){
761  for (int i = 0; i < 12; i++){
762  reportLeft.addDouble(0.0);
763  reportRight.addDouble(0.0);
764  }
765  }
766  for (int y = 0; y<4; y++){
767  for (int i = 0; i < 12; i++){
768  reportLeft.addDouble(resultLeft * 255);
769  reportRight.addDouble(resultRight * 255);
770  }
771  }
772  for (int y = 0; y<4; y++){
773  for (int i = 0; i < 12; i++){
774  reportLeft.addDouble(0.0);
775  reportRight.addDouble(0.0);
776  }
777  }
778  }
779  }
780  }//end lhand off rhand on
781  else{//both off
782  for (int x = 0; x < 6; x++){
783  double resultLeft=0, resultRight = 0;
784  if (boolean){
785  resultLeft = odeinit._iCub->checkTouchSensor( odeinit._iCub->l_hand );
786  resultRight = odeinit._iCub->checkTouchSensor( odeinit._iCub->r_hand );
787  }
788  else{
789  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( odeinit._iCub->l_hand );
790  resultRight = odeinit._iCub->checkTouchSensor_continuousValued(odeinit._iCub->r_hand);
791  }
792 
793  if (x < 5){
794  for (int i = 0; i < 12; i++){
795  reportLeft.addDouble(resultLeft * 255);
796  reportRight.addDouble(resultRight * 255);
797  }
798  }
799  if (x == 5){
800  for (int y = 0; y<3; y++){
801  for (int i = 0; i < 12; i++){
802  reportLeft.addDouble(0.0);
803  reportRight.addDouble(0.0);
804  }
805  }
806  for (int y = 0; y<4; y++){
807  for (int i = 0; i < 12; i++){
808  reportLeft.addDouble(resultLeft * 255);
809  reportRight.addDouble(resultRight * 255);
810  }
811  }
812  for (int y = 0; y<4; y++){
813  for (int i = 0; i < 12; i++){
814  reportLeft.addDouble(0.0);
815  reportRight.addDouble(0.0);
816  }
817  }
818  }
819  }
820  }//end both off
821 }
822 
823 
824 void OdeSdlSimulation::getAngles(const dReal *m, float& z, float& y, float& x) {
825  const dReal eps = 0.00001;
826 
827  y = -asin(m[2]);
828  float c = cos(y);
829 
830  if (fabs(c)>eps) {
831  x = atan2(-m[6]/c,m[10]/c);
832  z = atan2(-m[1]/c,m[0]/c);
833  } else {
834  x = 0;
835  z = -atan2(m[4],m[5]);
836  }
837  x *= -180/M_PI;
838  y *= 180/M_PI;
839  z *= 180/M_PI;
840 }
841 
842 void OdeSdlSimulation::initViewpoint() {
843  xpos = 0;
844  ypos = 1;
845  zpos = 1;
846  xrot = 25;
847  yrot = 0;
848  zrot = 0;
849 }
850 
851 void OdeSdlSimulation::mouseMovement(float x, float y) {
852  float diffx = x-lastx; //check the difference between the current x and the last x position
853  float diffy = y-lasty; //check the difference between the current y and the last y position
854  lastx =x; //set lastx to the current x position
855  lasty =y; //set lasty to the current y position
856  xrot += (float) diffy; //set the xrot to xrot with the addition of the difference in the y position
857  yrot += (float) diffx; //set the xrot to yrot with the addition of the difference in the x position
858 }
859 
860 void OdeSdlSimulation::draw_screen() {
861  OdeInit& odeinit = OdeInit::get();
862 
863  glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT); // refresh opengl
864 
865  if (extractImages || odeinit._iCub->actVision == "on"){
866  robot_streamer->sendVision();
867  }
868 
869  glViewport(0,0,width,height);
870  glMatrixMode (GL_PROJECTION);
871  glLoadIdentity();
872  gluPerspective( 75, (float)width/height, 0.01, 100.0 );
873  glMatrixMode (GL_MODELVIEW);
874  glLoadIdentity();
875  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
876  glRotatef (xrot, 1,0,0);
877  glRotatef (yrot, 0,1,0);
878  glRotatef (zrot, 0,0,1);
879  glTranslated(-xpos,-ypos,-zpos);
880 
881  // set up any video textures
882 
883  if (video!=0)
884  DrawVideo(video);
885 
886  //draw the ground
887  glColor3d(0.5,0.5,1);
888  glPushMatrix();
889  glRotatef(90.0,1,0,0);
890  glRotatef(180.0,0,1,0);
891  DrawGround(false);
892  glPopMatrix();
893  glDisable(GL_TEXTURE_2D);
894  draw();
895  glEnable(GL_TEXTURE_2D);
896  drawSkyDome(0,0,0,50,50,50); // Draw the Skybox
897  SDL_GL_SwapBuffers();// Swap Buffers
898 }
899 
900 
901 
902 void OdeSdlSimulation::retreiveInertialData(Bottle& inertialReport) {
903  OdeInit& odeinit = OdeInit::get();
904  static dReal OldLinearVel[3], LinearVel[3], LinearAccel[3];
905  inertialReport.clear();
906 
907  //get euler angles from quaternions
908  dQuaternion angles;
909  dGeomGetQuaternion( odeinit._iCub->inertialGeom, angles );
910  dReal w, x, y, z;
911  w = angles[0];
912  x = angles[1];
913  y = angles[2];
914  z = angles[3];
915 
916  double sqw = w * w;
917  double sqx = x * x;
918  double sqy = y * y;
919  double sqz = z * z;
920  float roll, pitch, yaw;
921 
922  double unit = sqx + sqy + sqz + sqw; // if normalised is one, otherwise is correction factor
923  double test = x*y + z*w;
924  if (test > 0.499*unit) { // singularity at north pole
925  roll = 2 * atan2(x,w);
926  pitch = M_PI/2;
927  yaw = 0;
928  return;
929  }
930  if (test < -0.499*unit) { // singularity at south pole
931  roll = -2 * atan2(x,w);
932  pitch = -M_PI/2;
933  yaw = 0;
934  return;
935  }
936  roll =(float) ( atan2(2.0*y*w-2*x*z , sqx - sqy - sqz + sqw) ); //z
937  pitch = (float) (atan2(2.0*x*w-2*y*z , -sqx + sqy - sqz + sqw) );//x
938  yaw = asin(2*test/unit);//y
939 
940  //roll = dBodyGetRotation(odeinit._iCub->head)[4]; // was 1
941  //pitch = dBodyGetRotation(odeinit._iCub->head)[6];
942  //yaw = dBodyGetRotation(odeinit._iCub->head)[2];
943 
944  //Add Euler angles roll pitch yaw
945  inertialReport.addDouble( -yaw * 180/M_PI);// yaw
946  inertialReport.addDouble( -pitch * 180/M_PI);// pitch
947  inertialReport.addDouble( roll * 180/M_PI);// roll
948 
949  /*//in order to calculate linear acceleration (make sure of body) Inertial Measurement Unit IMU
950  LinearVel[0] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[0];
951  LinearVel[1] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[1];
952  LinearVel[2] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[2];
954  LinearAccel[0] = ( LinearVel[0] - OldLinearVel[0] ) / 0.02;
955  LinearAccel[1] = ( LinearVel[1] - OldLinearVel[1] ) / 0.02;
956  LinearAccel[2] = ( LinearVel[2] - OldLinearVel[2] ) / 0.02;
957  OldLinearVel[0] = LinearVel[0];
958  OldLinearVel[1] = LinearVel[1];
959  OldLinearVel[2] = LinearVel[2];*/
960 
962  Vector grav,grav1,grav2,grav3;
963  grav.resize(3);
964  grav1.resize(3);
965  grav2.resize(3);
966  grav3.resize(3);
967  double theta;
968 
969  grav[0]=0;
970  grav[1]=0;
971  grav[2]=9.81;
972 
973  theta = pitch;
974  grav1[0]=grav[0]*cos(theta)+grav[2]*sin(theta);
975  grav1[1]=grav[1];
976  grav1[2]=grav[0]*(-sin(theta))+grav[2]*cos(theta);
977 
978  theta = yaw;
979  grav2[0]=grav1[0];
980  grav2[1]=grav1[1]*cos(theta)+grav1[2]*(-sin(theta));
981  grav2[2]=grav1[1]*sin(theta)+grav1[2]*cos(theta);
982 
983  theta = roll;
984  grav3[0]=grav2[0]*cos(theta)+grav2[1]*(-sin(theta));
985  grav3[1]=grav2[0]*sin(theta)+grav2[1]*cos(theta);
986  grav3[2]=grav2[2];
987 
988  inertialReport.addDouble( grav3[0] );
989  inertialReport.addDouble( grav3[1] );
990  inertialReport.addDouble( grav3[2] );
991 
992  //Add angular velocity
993  inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[2]*CTRL_RAD2DEG);
994  inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[0]*CTRL_RAD2DEG);
995  inertialReport.addDouble( dBodyGetAngularVel(odeinit._iCub->inertialBody)[1]*CTRL_RAD2DEG);
996 
997  //Add magnetic fields
998  inertialReport.addDouble(0.0);
999  inertialReport.addDouble(0.0);
1000  inertialReport.addDouble(0.0);
1001 }
1002 
1003 int OdeSdlSimulation::thread_ode(void *unused) {
1004  //SLD_AddTimer freezes the system if delay is too short. Instead use a while loop that waits if there was time left after the computation of ODE_process
1005  double cpms = 1e3 / CLOCKS_PER_SEC;
1006  long lastOdeProcess = (long) (clock()*cpms);
1007  double avg_ode_step_length = 0.0;
1008  long count = 0;
1009  simrun = true;
1010  double timeCache = ode_step_length;
1011  long lastTimeCacheUpdate = (long) (clock()*cpms);
1012  double alpha = 0.99;
1013  // if realTime=true when delays occur the simulation tries to recover by running more steps in a row
1014  // if realTime=false the simulation executes the simulation steps with a fixed rate irregardless of delays
1015  bool realTime = true;
1016  long temp;
1017 
1018  while (simrun) {
1019  temp = (long) (clock()*cpms);
1020  timeCache += temp - lastTimeCacheUpdate;
1021  lastTimeCacheUpdate = temp;
1022  while(timeCache < ode_step_length){
1023  SDL_Delay((unsigned int)(ode_step_length-timeCache));
1024  temp = (long) (clock()*cpms);
1025  timeCache += temp - lastTimeCacheUpdate;
1026  lastTimeCacheUpdate = temp;
1027  }
1028 
1029  /*if(timeCache >= 2.0*ode_step_length)
1030  printf("Simulation delay: running %d steps in a row to recover.\n", (int)(timeCache/ode_step_length));*/
1031 
1032  while(timeCache >= ode_step_length){
1033  count++;
1034  lastOdeProcess = (long) (clock()*cpms);
1035  ODE_process(1, (void*)1);
1036  avg_ode_step_length = alpha*avg_ode_step_length + (1.0-alpha)*((long) (clock()*cpms) -lastOdeProcess);
1037 
1038  if(realTime)
1039  timeCache -= ode_step_length;
1040  else
1041  timeCache = 0.0;
1042 
1043  // check if the desired timestep is achieved, if not, print a warning msg
1044  if(count % (10000/ode_step_length)==0){
1045  if(avg_ode_step_length >= ode_step_length+1)
1046  printf("WARNING: the simulation is too slow to run in real-time, you should increase the timestep in ode_params.ini (current value: %ld, suggested value: %.0f)\n",
1047  ode_step_length, avg_ode_step_length);
1048  else if(avg_ode_step_length <= ode_step_length-1)
1049  printf("INFO: you could get a more accurate dynamics simulation by decreasing the timestep in ode_params.ini (current value: %ld, suggested value: %.0f)\n",
1050  ode_step_length, avg_ode_step_length);
1051  }
1052  }
1053  }
1054  return(0);
1055 }
1056 
1057 Uint32 OdeSdlSimulation::ODE_process(Uint32 interval, void *param) {
1058  OdeInit& odeinit = OdeInit::get();
1059  //static clock_t startTimeODE= clock(), finishTimeODE= clock();
1060  //startTimeODE = clock();
1061 
1062  odeinit.mutex.wait();
1063  nFeedbackStructs=0;
1064 
1065  if (odeinit.verbosity > 3) printf("\n ***info code collision detection ***\n");
1066  if (odeinit.verbosity > 3) printf("OdeSdlSimulation::ODE_process: dSpaceCollide(odeinit.space,0,&nearCallback): will test iCub space against the rest of the world (e.g. ground).\n");
1067  dSpaceCollide(odeinit.space,0,&nearCallback); //determines which pairs of geoms in a space may potentially intersect, and calls a callback function with each candidate pair
1068  if (odeinit._iCub->actSelfCol == "on"){
1070  if (odeinit.verbosity > 3){
1071  printf("OdeSdlSimulation::ODE_process: dSpaceCollide(odeinit._iCub->iCub,0,&nearCallback): will test iCub subspaces against each other.\n");
1072  }
1073  dSpaceCollide(odeinit._iCub->iCub,0,&nearCallback); //determines which pairs of geoms in a space may potentially intersect, and calls a callback function with each candidate pair
1074  }
1075  }
1076  if (odeinit.verbosity > 3) printf("***END OF info code collision detection ***\n");
1077 
1078  dWorldStep(odeinit.world, dstep);
1079  // do 1 TIMESTEP in controllers (ok to run at same rate as ODE: 1 iteration takes about 300 times less computation time than dWorldStep)
1080  for (int ipart = 0; ipart<MAX_PART; ipart++) {
1081  if (odeinit._controls[ipart] != NULL) {
1082  odeinit._controls[ipart]->jointStep();
1083  }
1084  }
1085  odeinit.sync = true;
1086  odeinit.mutex.post();
1087 
1088  if (odeinit._iCub->actSkinEmul == "off"){
1089  if ( robot_streamer->shouldSendTouchLeftHand() || robot_streamer->shouldSendTouchRightHand() ) {
1090  Bottle reportLeft;
1091  Bottle reportRight;
1092  bool boolean = true;
1093  if (odeinit._iCub->actPressure == "on"){
1094  boolean = false;
1095  }
1096  inspectHandTouch_icubSensors(reportLeft, reportRight, boolean);//inspectBodyTouch_continuousValued(report);
1097 
1098  if ( robot_streamer->shouldSendTouchLeftHand() )
1099  robot_streamer->sendTouchLeftHand( reportLeft );
1100 
1101  if ( robot_streamer->shouldSendTouchRightHand() )
1102  robot_streamer->sendTouchRightHand( reportRight );
1103  }
1104  }
1105  else{ // actSkinEmul == "on"
1106  if(robot_streamer->shouldSendSkinEvents() || (robot_streamer->shouldSendTouchLeftHand() || robot_streamer->shouldSendTouchRightHand() ||
1107  robot_streamer->shouldSendTouchLeftArm() || robot_streamer->shouldSendTouchLeftForearm() ||
1108  robot_streamer->shouldSendTouchRightArm() || robot_streamer->shouldSendTouchRightForearm() ||
1109  robot_streamer->shouldSendTouchTorso())){
1110  if (! odeinit.listOfSkinContactInfos.empty()){ //if someone is reading AND there are contacts to process
1111  inspectWholeBodyContactsAndSendTouch();
1112  }
1113  else{ //someone is reading but no contacts, we send empty lists
1114  if(robot_streamer->shouldSendSkinEvents()){
1115  skinContactList emptySkinContactList;
1116  emptySkinContactList.clear();
1117  robot_streamer->sendSkinEvents(emptySkinContactList);
1118  }
1119  if(robot_streamer->shouldSendTouchLeftHand()){
1120  Bottle bottleLeftHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1121  robot_streamer->sendTouchLeftHand(bottleLeftHand);
1122  }
1123  if(robot_streamer->shouldSendTouchRightHand()){
1124  Bottle bottleRightHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1125  robot_streamer->sendTouchRightHand(bottleRightHand);
1126  }
1127  if(robot_streamer->shouldSendTouchLeftArm()){
1128  Bottle bottleLeftArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
1129  robot_streamer->sendTouchLeftArm(bottleLeftArm);
1130  }
1131  if(robot_streamer->shouldSendTouchLeftForearm()){
1132  Bottle bottleLeftForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
1133  robot_streamer->sendTouchLeftForearm(bottleLeftForearm);
1134  }
1135  if(robot_streamer->shouldSendTouchRightArm()){
1136  Bottle bottleRightArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
1137  robot_streamer->sendTouchRightArm(bottleRightArm);
1138  }
1139  if(robot_streamer->shouldSendTouchRightForearm()){
1140  Bottle bottleRightForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
1141  robot_streamer->sendTouchRightForearm(bottleRightForearm);
1142  }
1143  if(robot_streamer->shouldSendTouchTorso()){
1144  Bottle bottleTorso = Bottle(odeinit._iCub->emptySkinActivationTorso);
1145  robot_streamer->sendTouchTorso(bottleTorso);
1146  }
1147  }
1148  }
1149  odeinit.listOfSkinContactInfos.clear();
1150  resetContactICubSkinEmulMap();
1151  }
1152 
1153  dJointGroupEmpty (odeinit.contactgroup);
1154 
1155  if (robot_streamer->shouldSendInertial()) {
1156  Bottle inertialReport;
1157  retreiveInertialData(inertialReport);
1158  robot_streamer->sendInertial(inertialReport);
1159  }
1160 
1161  //go and check if torques are needed
1162  robot_streamer->checkTorques();
1163 
1164  odeinit._iCub->setJointControlAction();
1165 
1166  //finishTimeODE = clock() ;
1167  //SPS();
1168  //printf("ODE=%lf\n",(double)(finishTimeODE - startTimeODE) / CLOCKS_PER_SEC);
1169  return(interval);
1170 }
1171 
1172 
1173 /*int OdeSdlSimulation::thread_func(void *unused) {
1174  // this needs to be kept synchronized with the timestep in
1175  // dWorldStep, in order to get correct world clock time
1176  // --paulfitz
1177  int delay = 50;
1178  id = SDL_AddTimer( delay, &OdeSdlSimulation::ODE_process, (void*)1);
1179 
1180  return(0);
1181 }
1182 */
1183 /*
1184  static void SPS()
1185  {
1186  static float sps = 0.0f;
1187  static float previousTime = 0.0f;
1188  static int currentsps;
1189  static char strSPS[60] = {0};
1190 
1191  float currentTime = (GetTickCount() * 0.001f);
1192 
1193  ++sps; // Increment the SPS counter
1194 
1195  if( currentTime - previousTime > 1.0f ){
1196  previousTime = currentTime;
1197  currentsps = int(sps);
1198  printf("current SPS: %d\n",currentsps);
1199  sps = 0.0f;
1200  }
1201  }
1202 */
1203 
1204 void OdeSdlSimulation::sighandler(int sig) {
1205  OdeInit& odeinit = OdeInit::get();
1206  odeinit.stop = true;
1207  cout << "\nCAUGHT Ctrl-c" << endl;
1208 }
1209 
1210 void OdeSdlSimulation::simLoop(int h,int w) {
1211  fprintf(stdout, "***** OdeSdlSimulation::simLoop \n");
1212  OdeInit& odeinit = OdeInit::get();
1213 
1214  SDL_Init(SDL_INIT_TIMER | SDL_GL_ACCELERATED_VISUAL);
1215  SDL_SetVideoMode(h,w,32,SDL_OPENGL | SDL_RESIZABLE);// | SDL_SWSURFACE| SDL_ANYFORMAT); // on init
1216 
1217  dAllocateODEDataForThread(dAllocateMaskAll);
1218  ConstString logo = robot_config->getFinder().findFile("logo");
1219 
1220  image = SDL_LoadBMP(robot_config->getFinder().findFile(logo.c_str()).c_str());
1221  SDL_WM_SetIcon(image,0);
1222  SDL_FreeSurface(image);
1223  SDL_WM_SetCaption("iCub Simulator", "image");
1224 
1225  //SDL_Thread *thread;
1226  SDL_Thread *ode_thread = SDL_CreateThread(thread_ode, NULL);
1227  //thread = SDL_CreateThread(thread_func, NULL);
1228 
1229  if ( ode_thread == NULL ) {
1230  yError("Unable to create thread: %s\n", SDL_GetError());
1231  return;
1232  }
1233 
1234  initViewpoint();
1235  bool ok = setup_opengl(robot_config->getFinder());
1236  if (!ok) return;
1237  startTime = (long) clock();
1238  odeinit.stop = false;
1239 
1240  yarp::os::signal(yarp::os::YARP_SIGINT, sighandler);
1241  yarp::os::signal(yarp::os::YARP_SIGTERM, sighandler);
1242 
1243  glrun = true;
1244  odeinit._wrld->WAITLOADING = false;
1245  odeinit._wrld->static_model = false;
1246  long prevTime = (long) clock();
1247  long timeLeft;
1248 
1249  if (odeinit._iCub->actStartHomePos == "on"){
1250  odeinit.sendHomePos();
1251  }
1252  if (odeinit._iCub->actSelfCol == "on") {
1253  if (odeinit._iCub->actStartHomePos == "on"){
1254  Time::delay(2.0); //we want to set this trigger on only after the robot is in home pos -
1255  //it's initial configuration is with arms inside the thighs - generating many self-collisions
1257  }
1258  else{
1259  fprintf(stdout, "Warning: the robot is not starting from HomePos and self-collision mode is on. The initial posture is already self-colliding.\n");
1261  }
1262  }
1263 
1264  while(!odeinit.stop) {
1265  /* Process incoming events. */
1266  process_events();
1267  /* Draw the screen. */
1268  if ( !odeinit._wrld->WAITLOADING ){
1269  if (glrun) {
1270  odeinit.mutexTexture.wait();
1271  draw_screen();
1272  odeinit.mutexTexture.post();
1273  // check for framerate
1274  timeLeft = (prevTime - (long) clock()) + gl_frame_length;
1275  //cout << "check for framerate " << timeLeft << endl;
1276  if (timeLeft > 0)
1277  { // if there is still time left in this frame, just wait
1278  SDL_Delay(timeLeft);
1279  }
1280  prevTime = (long) clock();
1281  } else {
1282  SDL_Delay(100);
1283  }
1284  }
1285  else{
1286  glFinish();
1287  glFlush();
1288  //make sure it can also be done for static objects
1289  if (odeinit._wrld->static_model){
1290  odeinit._wrld->loadTexture(odeinit._wrld->texture, odeinit._wrld->s_modelTexture[odeinit._wrld->s_MODEL_NUM-1]);
1291  }else{
1292  odeinit._wrld->loadTexture(odeinit._wrld->texture, odeinit._wrld->modelTexture[odeinit._wrld->MODEL_NUM-1]);
1293  }
1294  odeinit._wrld->WAITLOADING = false;
1295  odeinit._wrld->static_model = false;
1296  }
1297  }
1298  printf("\n\nStopping SDL and ODE threads...\n");
1299  //stop the timer
1300  //SDL_RemoveTimer(id);
1301  //Stop the thread
1302  //SDL_KillThread( thread );
1303  simrun = false;
1304  //SDL_WaitThread( thread, NULL );
1305  SDL_WaitThread( ode_thread, NULL );
1306  //SDL_Quit();
1307 }
1308 
1309 void OdeSdlSimulation::drawView(bool left, bool right, bool wide) {
1310  OdeInit& odeinit = OdeInit::get();
1311  const dReal *pos;
1312  const dReal *rot;
1313  glViewport(0,0,cameraSizeWidth,cameraSizeHeight);
1314  glMatrixMode (GL_PROJECTION);
1315 
1316  if (left){
1317  glLoadIdentity();
1318  gluPerspective( fov_left, (float) width_left/height_left, 0.04, 100.0 );
1319  pos = dGeomGetPosition(odeinit._iCub->Leye1_geom);
1320  rot = dGeomGetRotation(odeinit._iCub->Leye1_geom);
1321  glMatrixMode (GL_MODELVIEW);
1322  glLoadIdentity();
1323  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1324  gluLookAt(
1325  pos[0],
1326  pos[1],
1327  pos[2],
1328  pos[0] + rot[2],
1329  pos[1] + rot[6],
1330  pos[2] + rot[10],
1331  -rot[4], 1, 0
1332  );
1333  }
1334  if (right){
1335  glLoadIdentity();
1336  gluPerspective( fov_right, (float) width_right/height_right, 0.04, 100.0 );//55.8
1337  pos = dGeomGetPosition(odeinit._iCub->Reye1_geom);
1338  rot = dGeomGetRotation(odeinit._iCub->Reye1_geom);
1339  glMatrixMode (GL_MODELVIEW);
1340  glLoadIdentity();
1341  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1342  gluLookAt(
1343  pos[0],
1344  pos[1],
1345  pos[2],
1346  pos[0] + rot[2],
1347  pos[1] + rot[6],
1348  pos[2] + rot[10],
1349  -rot[4], 1, 0
1350  );
1351  }
1352  if (wide){
1353  glLoadIdentity();
1354  gluPerspective( 55.8, (float) cameraSizeWidth/cameraSizeHeight, 0.04, 100.0 );//here nothing to do with cameras
1355  glMatrixMode (GL_MODELVIEW);
1356  glLoadIdentity();
1357  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1358  glRotatef (xrot, 1,0,0);
1359  glRotatef (yrot, 0,1,0);
1360  glTranslated(-xpos,-ypos,-zpos);
1361  }
1362 
1363  //draw the ground
1364  glColor3d(0.5,0.5,1);
1365  glEnable(GL_TEXTURE_2D);
1366  glPushMatrix();
1367  glRotatef(90.0,1,0,0);
1368  glRotatef(180.0,0,1,0);
1369  DrawGround(false);
1370  glPopMatrix();
1371  glDisable(GL_TEXTURE_2D);
1372  draw();//robot
1373  glEnable(GL_TEXTURE_2D);
1374  drawSkyDome(0,0,0,50,50,50); // Draw the Skybox
1375 }
1376 
1378  glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT); // refresh opengl
1379 }
1380 
1382 }
1383 
1385  RobotConfig *config) {
1386  OdeInit& odeinit = OdeInit::get();
1387  if (video!=NULL) {
1388  fprintf(stderr, "Only one Simulation object allowed\n");
1389  yarp::os::exit(1);
1390  }
1391  robot_streamer = streamer;
1392  robot_config = config;
1393 
1394  ode_step_length = config->getWorldTimestep();
1395  dstep = ode_step_length*1e-3;
1396 
1397  video = new VideoTexture;
1398  string moduleName = odeinit.getName();
1399  video->setName( moduleName );
1400  odeinit._iCub->eyeLidsPortName = moduleName;
1401  Property options;
1402 
1403  //get the camera calibration parameters
1404  string camcalib_context=robot_config->getFinder().check("camcalib_context",
1405  Value("cameraCalibration")).asString().c_str();
1406  string camcalib_file=robot_config->getFinder().check("camcalib_file",
1407  Value("icubSimEyes.ini")).asString().c_str();
1408 
1409  ResourceFinder rf_camcalib;
1410  rf_camcalib.setVerbose();
1411  rf_camcalib.setDefaultContext(camcalib_context.c_str());
1412  rf_camcalib.setDefaultConfigFile(camcalib_file.c_str());
1413  rf_camcalib.configure(0,NULL);
1414 
1415  //left
1416  Bottle &bCalibLeft=rf_camcalib.findGroup("CAMERA_CALIBRATION_LEFT");
1417  width_left=bCalibLeft.check("w",Value(320)).asInt();
1418  height_left=bCalibLeft.check("h",Value(240)).asInt();
1419 
1422 
1423  double focal_length_left=bCalibLeft.check("fy",Value(257.34)).asDouble();
1424  fov_left=2*atan2((double)height_left,2*focal_length_left)*180.0/M_PI;
1425 
1426  //right
1427  Bottle &bCalibRight=rf_camcalib.findGroup("CAMERA_CALIBRATION_RIGHT");
1428  width_right=bCalibRight.check("w",Value(320)).asInt();
1429  height_right=bCalibRight.check("h",Value(240)).asInt();
1430 
1431  double focal_length_right=bCalibRight.check("fy",Value(257.34)).asDouble();
1432  fov_right=2*atan2((double)height_right,2*focal_length_right)*180.0/M_PI;
1433  //--------------------------------------//
1434 
1435 
1436  ConstString videoconf = robot_config->getFinder().findFile("video");
1437  options.fromConfigFile(videoconf.c_str());
1438 
1439  Bottle textures = *options.find("textures").asList();
1440  for (int i=0; i<textures.size(); i++) {
1441  ConstString name = textures.get(i).asString();
1442  printf("Adding video texture %s\n", name.c_str());
1443  video->add(options.findGroup(name.c_str()));
1444  }
1445 
1446  initContactICubSkinEmulMap();
1447 
1448 };
1449 
1450 void OdeSdlSimulation::initContactICubSkinEmulMap(void)
1451 {
1452 
1453  contactICubSkinEmul_t skin_emul_struct;
1454 
1455  //SKIN_LEFT_HAND
1456  skin_emul_struct.coverTouched = false; //for the hand, this comprises also fingertips - they are treated like covers
1457  skin_emul_struct.indivTaxelResolution = true;
1458  contactICubSkinEmulMap[SKIN_LEFT_HAND]=skin_emul_struct;
1459 
1460  //SKIN_LEFT_FOREARM
1461  skin_emul_struct.coverTouched = false;
1462  skin_emul_struct.indivTaxelResolution = false;
1463  contactICubSkinEmulMap[SKIN_LEFT_FOREARM]=skin_emul_struct;
1464 
1465  //SKIN_LEFT_UPPER_ARM
1466  skin_emul_struct.coverTouched = false;
1467  skin_emul_struct.indivTaxelResolution = false;
1468  contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM]=skin_emul_struct;
1469 
1470  //SKIN_RIGHT_HAND
1471  skin_emul_struct.coverTouched = false; //for the hand, this comprises also fingertips - they are treated like covers
1472  skin_emul_struct.indivTaxelResolution = true;
1473  contactICubSkinEmulMap[SKIN_RIGHT_HAND]=skin_emul_struct;
1474 
1475  //SKIN_RIGHT_FOREARM
1476  skin_emul_struct.coverTouched = false;
1477  skin_emul_struct.indivTaxelResolution = false;
1478  contactICubSkinEmulMap[SKIN_RIGHT_FOREARM]=skin_emul_struct;
1479 
1480  //SKIN_RIGHT_UPPER_ARM
1481  skin_emul_struct.coverTouched = false;
1482  skin_emul_struct.indivTaxelResolution = false;
1483  contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM]=skin_emul_struct;
1484 
1485  //SKIN_FRONT_TORSO
1486  skin_emul_struct.coverTouched = false;
1487  skin_emul_struct.indivTaxelResolution = false;
1488  contactICubSkinEmulMap[SKIN_FRONT_TORSO]=skin_emul_struct;
1489 
1490  //LEFT_LEG_UPPER
1491  skin_emul_struct.coverTouched = false;
1492  skin_emul_struct.indivTaxelResolution = false;
1493  contactICubSkinEmulMap[LEFT_LEG_UPPER]=skin_emul_struct;
1494 
1495  //LEFT_LEG_LOWER
1496  skin_emul_struct.coverTouched = false;
1497  skin_emul_struct.indivTaxelResolution = false;
1498  contactICubSkinEmulMap[LEFT_LEG_LOWER]=skin_emul_struct;
1499 
1500  //LEFT_FOOT
1501  skin_emul_struct.coverTouched = false;
1502  skin_emul_struct.indivTaxelResolution = false;
1503  contactICubSkinEmulMap[LEFT_FOOT]=skin_emul_struct;
1504 
1505  //RIGHT_LEG_UPPER
1506  skin_emul_struct.coverTouched = false;
1507  skin_emul_struct.indivTaxelResolution = false;
1508  contactICubSkinEmulMap[RIGHT_LEG_UPPER]=skin_emul_struct;
1509 
1510  //RIGHT_LEG_LOWER
1511  skin_emul_struct.coverTouched = false;
1512  skin_emul_struct.indivTaxelResolution = false;
1513  contactICubSkinEmulMap[RIGHT_LEG_LOWER]=skin_emul_struct;
1514 
1515  //RIGHT_FOOT
1516  skin_emul_struct.coverTouched = false;
1517  skin_emul_struct.indivTaxelResolution = false;
1518  contactICubSkinEmulMap[RIGHT_FOOT]=skin_emul_struct;
1519 
1520 // if (odeinit.verbosity > 2){
1521 // printf("OdeSdlSimulation::initContactICubSkinEmulMap \n");
1522 // for (std::map<SkinPart,contactICubSkinEmul_t>::const_iterator it=contactICubSkinEmulMap.begin(); it!=contactICubSkinEmulMap.end(); ++it){
1523 // printf("key: %d, cover touched: %d, indivTaxelResolution: %d \n", it->first,it->second.coverTouched,it->second.indivTaxelResolution);
1524 // }
1525 // }
1526 }
1527 
1528 void OdeSdlSimulation::resetContactICubSkinEmulMap(void)
1529 {
1530 
1531  //SKIN_LEFT_HAND
1532  contactICubSkinEmulMap[SKIN_LEFT_HAND].coverTouched="false";
1533  contactICubSkinEmulMap[SKIN_LEFT_HAND].taxelsTouched.clear();
1534 
1535  //SKIN_LEFT_FOREARM
1536  contactICubSkinEmulMap[SKIN_LEFT_FOREARM].coverTouched="false";
1537  contactICubSkinEmulMap[SKIN_LEFT_FOREARM].taxelsTouched.clear();
1538 
1539  //SKIN_LEFT_UPPER_ARM
1540  contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].coverTouched="false";
1541  contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].taxelsTouched.clear();
1542 
1543  //SKIN_RIGHT_HAND
1544  contactICubSkinEmulMap[SKIN_RIGHT_HAND].coverTouched="false";
1545  contactICubSkinEmulMap[SKIN_RIGHT_HAND].taxelsTouched.clear();
1546 
1547  //SKIN_RIGHT_FOREARM
1548  contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].coverTouched="false";
1549  contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].taxelsTouched.clear();
1550 
1551  //SKIN_RIGHT_UPPER_ARM
1552  contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].coverTouched="false";
1553  contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].taxelsTouched.clear();
1554 
1555  //SKIN_FRONT_TORSO
1556  contactICubSkinEmulMap[SKIN_FRONT_TORSO].coverTouched="false";
1557  contactICubSkinEmulMap[SKIN_FRONT_TORSO].taxelsTouched.clear();
1558 
1559  //LEFT_LEG_UPPER
1560  contactICubSkinEmulMap[LEFT_LEG_UPPER].coverTouched="false";
1561  contactICubSkinEmulMap[LEFT_LEG_UPPER].taxelsTouched.clear();
1562 
1563  //LEFT_LEG_LOWER
1564  contactICubSkinEmulMap[LEFT_LEG_LOWER].coverTouched="false";
1565  contactICubSkinEmulMap[LEFT_LEG_LOWER].taxelsTouched.clear();
1566 
1567  //LEFT_FOOT
1568  contactICubSkinEmulMap[LEFT_FOOT].coverTouched="false";
1569  contactICubSkinEmulMap[LEFT_FOOT].taxelsTouched.clear();
1570 
1571  //RIGHT_LEG_UPPER
1572  contactICubSkinEmulMap[RIGHT_LEG_UPPER].coverTouched="false";
1573  contactICubSkinEmulMap[RIGHT_LEG_UPPER].taxelsTouched.clear();
1574 
1575  //RIGHT_LEG_LOWER
1576  contactICubSkinEmulMap[RIGHT_LEG_LOWER].coverTouched="false";
1577  contactICubSkinEmulMap[RIGHT_LEG_LOWER].taxelsTouched.clear();
1578 
1579  //RIGHT_FOOT
1580  contactICubSkinEmulMap[RIGHT_FOOT].coverTouched="false";
1581  contactICubSkinEmulMap[RIGHT_FOOT].taxelsTouched.clear();
1582 }
1583 
1584 
1585 
1587  delete video;
1588 }
1589 
1590 
1592  OdeInit& odeinit = OdeInit::get();
1593  if (reset) {
1594  odeinit.sync = false;
1595  }
1596  return odeinit.sync;
1597 }
1598 
1599 
1600 bool OdeSdlSimulation::getTrqData(Bottle data) {
1601  OdeInit& odeinit = OdeInit::get();
1602  for (int s=0; s<data.size(); s++){
1603  odeinit._iCub->torqueData[s] = data.get(s).asDouble();
1604  //fprintf(stdout,"torques... %lf \n",odeinit._iCub->torqueData[s]);
1605  }
1606  return true;
1607 }
1608 
1609 
1610 
1611 bool OdeSdlSimulation::getImage(ImageOf<PixelRgb>& target) {
1612  int w = cameraSizeWidth;
1613  int h = cameraSizeHeight;
1614  int p = 3;
1615 
1616  char *buf=new char[w * h * p];
1617  glReadPixels( 0, 0, w, h, GL_RGB, GL_UNSIGNED_BYTE, buf);
1618  ImageOf<PixelRgb> img;
1619  img.setQuantum(1);
1620  img.setExternal(buf,w,h);
1621 
1622  // inefficient flip!
1623  target.resize(img);
1624  int ww = img.width();
1625  int hh = img.height();
1626  for (int x=0; x<ww; x++) {
1627  for (int y=0; y<hh; y++) {
1628  target(x,y) = img(x,hh-1-y);
1629  }
1630  }
1631  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
1632  delete[] buf;
1633  return true;
1634 }
1635 
1636 void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch()
1637 {
1638  //SkinDynLib enums
1639  SkinPart skinPart; // id of the part of the skin (e.g. SKIN_LEFT_FOREARM; from skinDynLib/common.h)
1640  BodyPart bodyPart; // id of the body part
1641  HandPart handPart; // id of the hand part - INDEX, MIDDLE, RING, LITTLE, THUMB, PALM, ALL_HAND_PARTS, HAND_PART_SIZE
1642 
1643  //coordinate transformations for skinEvents and for emulating ind. taxel groups per skin part
1644  Vector geoCenter_SIM_FoR_forHomo(4,0.0), normal_SIM_FoR_forHomo(4,0.0);
1645  Vector force_SIM_FoR_forHomo(4,0.0), moment_SIM_FoR_forHomo(4,0.0);
1646  Vector v1(4,0.0); //auxilliary vector
1647  Vector geoCenter_link_FoR(3,0.0), normal_link_FoR(3,0.0);
1648  Vector force_link_FoR(3,0.0), moment_link_FoR(3,0.0);
1649  double forceOnBody_magnitude;
1650  double left_arm_encoders[16], right_arm_encoders[16], torso_encoders[3], head_encoders[6];
1651  Vector left_arm_for_iKin(10,0.0), right_arm_for_iKin(10,0.0), inertial_for_iKin(6,0.0);
1652  Matrix T_root_to_link = yarp::math::zeros(4,4);
1653  Matrix T_link_to_root = yarp::math::zeros(4,4);
1654  std::vector<unsigned int> taxel_list;
1655  bool upper_body_transforms_available = false;
1656 
1657  bool skinCoverFlag = false;
1658  bool fingertipFlag = true;
1659  bool left_hand_notCover_touched = false;
1660  bool right_hand_notCover_touched = false;
1661  OdeInit& odeinit = OdeInit::get();
1662  skinContactList mySkinContactList;
1663  mySkinContactList.clear();
1664 
1665  if ((odeinit._iCub->actHead=="off") || (odeinit._iCub->actTorso=="off") || (odeinit._iCub->actLArm=="off") || (odeinit._iCub->actRArm=="off")){
1666  upper_body_transforms_available = false;
1667  printf("Warning: With self-collisions on but head/torso/left_arm/right_arm off, the upper body transforms are unavailable and skinContactList can't be created.\n");
1668  }
1669  else{
1670  upper_body_transforms_available = true;
1671 
1672  odeinit._controls[PART_ARM_LEFT]->getEncodersRaw(left_arm_encoders);
1673  odeinit._controls[PART_ARM_RIGHT]->getEncodersRaw(right_arm_encoders);
1674  odeinit._controls[PART_TORSO]->getEncodersRaw(torso_encoders);
1675  odeinit._controls[PART_HEAD]->getEncodersRaw(head_encoders); //first three are probably neck joints, then the eyes
1676  for (int j=0;j<TORSO_DOF;j++){
1677  left_arm_for_iKin(j)=torso_encoders[j]; //first 3 joints - 0 to 2 - in iKin arm are torso joints
1678  right_arm_for_iKin(j)=torso_encoders[j];
1679  inertial_for_iKin(j)=torso_encoders[j];
1680  }
1681  for (int l=0;l<7;l++){
1682  left_arm_for_iKin(l+TORSO_DOF) = left_arm_encoders[l]; // then we put seven arm joints (we ignore the rest of the encoders up to 16 - these are fingers)
1683  right_arm_for_iKin(l+TORSO_DOF) = right_arm_encoders[l];
1684  }
1685  for (int m=0;m<3;m++){
1686  inertial_for_iKin(m+TORSO_DOF) = head_encoders[m]; //we put the second three - the neck joints and ignore the rest of head_encoders (the eyes)
1687  }
1688  odeinit._iCub->iKinLeftArm.setAng(left_arm_for_iKin);
1689  odeinit._iCub->iKinRightArm.setAng(right_arm_for_iKin);
1690  odeinit._iCub->iKinInertialSensor.setAng(inertial_for_iKin);
1691  }
1692 
1693  if (odeinit.verbosity > 4) printf("OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch:There were %lu iCub collisions to process. \n", odeinit.listOfSkinContactInfos.size());
1694  //main loop through all the contacts
1695  for (list<OdeInit::contactOnSkin_t>::iterator it = odeinit.listOfSkinContactInfos.begin(); it!=odeinit.listOfSkinContactInfos.end(); it++){
1696  skinPart = SKIN_PART_UNKNOWN; bodyPart = BODY_PART_UNKNOWN; handPart = ALL_HAND_PARTS; fingertipFlag = false;
1697  taxel_list.clear();
1698  odeinit._iCub->getSkinAndBodyPartFromSpaceAndGeomID((*it).body_geom_space_id,(*it).body_geom_id,skinPart,bodyPart,handPart,skinCoverFlag,fingertipFlag);
1699  if(upper_body_transforms_available){
1700  geoCenter_SIM_FoR_forHomo.zero(); geoCenter_SIM_FoR_forHomo(3)=1.0; //setting the extra row to 1 - for multiplication by homogenous rototransl. matrix
1701  normal_SIM_FoR_forHomo.zero(); normal_SIM_FoR_forHomo(3)=1.0;
1702  force_SIM_FoR_forHomo.zero(); force_SIM_FoR_forHomo(3)=1.0;
1703  moment_SIM_FoR_forHomo.zero(); moment_SIM_FoR_forHomo(3)=1.0;
1704  geoCenter_link_FoR.zero();normal_link_FoR.zero();
1705  moment_link_FoR.zero();force_link_FoR.zero();
1706  forceOnBody_magnitude=0.0;
1707  T_root_to_link.zero(); T_link_to_root.zero();
1708  for (int i=0;i<3;i++){
1709  geoCenter_SIM_FoR_forHomo(i)= (*it).contact_geom.pos[i]; //in global (i.e. simulator) coordinates
1710  normal_SIM_FoR_forHomo(i) = (*it).contact_geom.normal[i];
1711  }
1712  dJointFeedback * fb = dJointGetFeedback ((*it).contact_joint);
1713  if (fb==NULL){
1714  printf("Warning:OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch: This joint (at %d skin part) has no feedback structure defined - contact force not available: setting to -1.\n",skinPart);
1715  forceOnBody_magnitude = -1;
1716  }
1717  else{
1718  //printf("OdeSdlSimulation::processWholeBodyCollisions: joint feedback structure:\n.");
1719  //printf("f1 force vector in simulator FoR: %f %f %f \n",fb->f1[0],fb->f1[1],fb->f1[2]); // assuming it is global ODE FoR ~ simulator FoR
1720  //printf("f2 force vector: %f %f %f \n",fb->f2[0],fb->f2[1],fb->f2[2]);
1721  //f2 force vector has same magnitude but opposite direction than f1
1722  for(int k=0;k<3;k++){
1723  if((*it).body_index == 1){
1724  force_SIM_FoR_forHomo(k)=fb->f1[k];
1725  moment_SIM_FoR_forHomo(k)=fb->t1[k];
1726  }
1727  else if((*it).body_index == 2){
1728  force_SIM_FoR_forHomo(k)=fb->f2[k];
1729  moment_SIM_FoR_forHomo(k)=fb->t2[k];
1730  }
1731  else{
1732  yError("OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch: unexpected body_index for colliding body: %d.\n",(*it).body_index);
1733  }
1734  }
1735  forceOnBody_magnitude=sqrt(force_SIM_FoR_forHomo(0)*force_SIM_FoR_forHomo(0) + force_SIM_FoR_forHomo(1)*force_SIM_FoR_forHomo(1)
1736  + force_SIM_FoR_forHomo(2)*force_SIM_FoR_forHomo(2));
1737  }
1738  //Let's do all the transformations
1739  //Assuming, dJointFeedback and contact_geom data from ODE are in global ODE frame; the contact_geom.pos is the position; the contact_geom.normal and the dJointFeedback
1740  // vectors (f1, m1) are originating from the global origin, i.e. they need to be translated to contact_geom.pos;
1741  //see the post in ode-users group "dJointFeedback and dContactGeom reference frame", 6.12.2013; local FoR of the contact point;
1742 
1743  switch(bodyPart){
1744  case LEFT_ARM:
1745  T_root_to_link = odeinit._iCub->iKinLeftArm.getH(SkinPart_2_LinkNum[skinPart].linkNum + TORSO_DOF);
1746  //e.g. skinPart LEFT_UPPER_ARM gives link number 2, which means we ask iKin for getH(2+3), which gives us FoR 6 - at the first elbow joint, which is the FoR for the upper arm
1747  break;
1748  case RIGHT_ARM:
1749  T_root_to_link = odeinit._iCub->iKinRightArm.getH(SkinPart_2_LinkNum[skinPart].linkNum + TORSO_DOF);
1750  break;
1751  case TORSO:
1752  T_root_to_link = odeinit._iCub->iKinInertialSensor.getH(SkinPart_2_LinkNum[skinPart].linkNum);
1753  // SkinPart_2_LinkNum[SKIN_FRONT_TORSO].linkNum is 2, this should give us the FoR 3 - the first neck joint which is the expected torso FoR
1754  //- check " SKIN torso 2" in iCub/main/app/iCubGui/skeleton.ini
1755  //- importantly, this needs to be the iKinInertialSensor, not the iKin Arm;
1756  break;
1757  default:
1758  if (odeinit.verbosity > 0) printf("OdeSdlSimulation::processWholeBodyCollisions: FoR transforms to BODY PART %d not implemented yet\n",bodyPart);
1759  continue;
1760  }
1761  T_link_to_root = SE3inv(T_root_to_link);
1762 
1763  v1.zero();
1764  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * geoCenter_SIM_FoR_forHomo; //first transform to robot coordinates, then transform to local FoR of respective body part
1765  geoCenter_link_FoR = v1.subVector(0,2); //strip the last one away
1766 
1767  v1.zero();
1768  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * normal_SIM_FoR_forHomo;
1769  normal_link_FoR = v1.subVector(0,2);
1770 
1771  v1.zero();
1772  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * force_SIM_FoR_forHomo;
1773  force_link_FoR = v1.subVector(0,2);
1774 
1775  v1.zero();
1776  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * moment_SIM_FoR_forHomo;
1777  moment_link_FoR = v1.subVector(0,2);
1778 
1779  //Note that the normal, force, and moment are just carrying the orientation (and apart from the normal also magnitude) - they will still need to be translated to the
1780  //appropariate CoP / geoCenter to make the arrow to the taxel
1781  //Note also the dJointFeedback force vector does not necessarily point along the normal at the contact point (which points into the colliding body) - as is a sum of the
1782  //forces along the normal and frictional forces perpendicular to the normal
1783  //alternatively, I could just take the magnitude from the force and send the normal as the direction
1784 
1785  //printf("Contact coordinates in ODE / SIM FoR: %s\n",geoCenter_SIM_FoR_forHomo.subVector(0,2).toString().c_str());
1786  Vector temp_v4(4,0.0);
1787  temp_v4 = (odeinit._iCub->H_r2w) * geoCenter_SIM_FoR_forHomo;
1788  //printf("Contact coordinates in robot root FoR: %s\n",temp_v4.subVector(0,2).toString().c_str());
1789  //printf("Left arm for iKin:\n %s \n",left_arm_for_iKin.toString().c_str());
1790  //printf("Rototranslation matrix root to link:\n %s\n",T_root_to_link.toString().c_str());
1791  //printf("Contact coordinates in link FoR: %s\n",geoCenter_link_FoR.toString().c_str());
1792  /*for (int l=0;l<2;l++){ geoCenter_link_FoR(l)=0.0; force_link_FoR(l)=1.0; normal_link_FoR(l)=1.0; moment_link_FoR(l)=1.0;
1793  } */
1794  //forceOnBody_magnitude=10.0;
1795  if (contactICubSkinEmulMap[skinPart].indivTaxelResolution && (skinCoverFlag || fingertipFlag)){ //indiv taxels get emulated only on covers - where the actual skin is
1796  if(skinCoverFlag){
1797  mapPositionIntoTaxelList(skinPart,geoCenter_link_FoR,taxel_list);
1798  }
1799  else if(fingertipFlag){
1800  mapFingertipIntoTaxelList(handPart,taxel_list);
1801  }
1802  }
1803  else{
1804  taxel_list.push_back(FAKE_TAXEL_ID); // we will emulate one non-existent activated "taxel" per contact joint - say taxel "10000"
1805  }
1806  skinContact c(bodyPart, skinPart, getLinkNum(skinPart), geoCenter_link_FoR, geoCenter_link_FoR,taxel_list, forceOnBody_magnitude, normal_link_FoR,force_link_FoR,moment_link_FoR);
1807  //we have only one source of information - the contact as detected by ODE - therefore, we take the coordinates and set them both to CoP
1808  //(which is supposed to come from the dynamic estimation, and as geoCenter - from skin; Similarly, we derive the pressure directly from the force vector from ODE.
1809  if (odeinit.verbosity > 4) printf("Creating skin contact as follows: %s.\n",c.toString().c_str());
1810  mySkinContactList.push_back(c);
1811  } //if(upper_body_transforms_available){
1812  // here we collect the info for emulating the skin ports (compensated tactile ports)
1813  if(skinCoverFlag || fingertipFlag){
1814  //if it was a cover (including palm cover) or fingertip that was touched, we will append the taxels touched to respective contactICubSkinEmulMap
1815  contactICubSkinEmulMap[skinPart].coverTouched = true;
1816  if (contactICubSkinEmulMap[skinPart].indivTaxelResolution){
1817  if (!taxel_list.empty()){
1818  unsigned int first_taxel_in_list = taxel_list[0];
1819  if (first_taxel_in_list != FAKE_TAXEL_ID){
1820  for (std::vector<unsigned int>::const_iterator it = taxel_list.begin() ; it != taxel_list.end(); ++it){
1821  contactICubSkinEmulMap[skinPart].taxelsTouched.insert(*it); //inserting the taxel IDs into the set
1822  }
1823  }
1824  }
1825  }
1826  }
1827  } //cycle through odeinit.listOfSkinContactInfos
1828 
1829  //all contacts have been processed, now we produce the output
1830 
1831  if(robot_streamer->shouldSendSkinEvents()){ //note that these are generated here for any body parts - not only those that have tactile sensors in the real robot
1832  // the contacts can be visualized using the icubGui (not skinGui)
1833  robot_streamer->sendSkinEvents(mySkinContactList); //we send even if empty
1834  }
1835 
1836  //for hands, this is now done differently than in the original inspectTouch_icubSensors, where finger bodies were inspected, whether they have contact joints attached to them
1837  // the palm cover replaces sensing in the palm body
1838  //now all info about contacts has come from cycling through the odeinit.listOfSkinContactInfos above and it has beem filled into appropriate structs
1839  //the output of actual pressure values is discontinued;
1840  int y=0;
1841  if(robot_streamer->shouldSendTouchLeftHand()){
1842  Bottle bottleLeftHand;
1843  if (contactICubSkinEmulMap[SKIN_LEFT_HAND].coverTouched){
1844  //prepare the bottle
1845  //first 60 are fingers
1846  if (contactICubSkinEmulMap[SKIN_LEFT_HAND].indivTaxelResolution){
1847  for (y = 0; y<=59; y++){
1848  if (contactICubSkinEmulMap[SKIN_LEFT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1849  bottleLeftHand.addDouble(255.0);
1850  }
1851  else{
1852  bottleLeftHand.addDouble(0.0);
1853  }
1854  }
1855  }
1856  else{ //we fill them all
1857  for (y = 0; y<=59; y++){
1858  bottleLeftHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now
1859  }
1860  }
1861  //zero padding - the port output: 61-96 zeros; taxel IDs 60-95
1862  for (y = 60; y<=95; y++){
1863  bottleLeftHand.addDouble(0.0);
1864  }
1865 
1866  //pam - positions 97-144 palm taxels; taxel IDs have index by one lower (inside these, IDs 107, 119, 131, and 139 are thermal pads ~ 0s);
1867  if (contactICubSkinEmulMap[SKIN_LEFT_HAND].indivTaxelResolution){
1868  for (y = 96; y<=143; y++){
1869  if (contactICubSkinEmulMap[SKIN_LEFT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1870  bottleLeftHand.addDouble(255.0);
1871  }
1872  else{
1873  bottleLeftHand.addDouble(0.0);
1874  }
1875  }
1876  }
1877  else{ //we fill the whole palm
1878  for (int y = 96; y<=143; y++){
1879  bottleLeftHand.addDouble(255.0); //we ignore the thermal pad positions, which should be 0s, for now
1880  }
1881  }
1882  //filling the rest: 145-192 zeros. IDs: 144-191
1883  for (int y = 144; y<=191; y++){
1884  bottleLeftHand.addDouble(0.0);
1885  }
1886  }
1887  else{
1888  bottleLeftHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1889  }
1890  robot_streamer->sendTouchLeftHand(bottleLeftHand);
1891  }
1892 
1893 
1894  if(robot_streamer->shouldSendTouchRightHand()){
1895  Bottle bottleRightHand;
1896  if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].coverTouched){
1897  //prepare the bottle
1898  //first 60 are fingers
1899  if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].indivTaxelResolution){
1900  for (y = 0; y<=59; y++){
1901  if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1902  bottleRightHand.addDouble(255.0);
1903  }
1904  else{
1905  bottleRightHand.addDouble(0.0);
1906  }
1907  }
1908  }
1909  else{ //we fill them all
1910  for (y = 0; y<=59; y++){
1911  bottleRightHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now
1912  }
1913  }
1914  //zero padding - the port output: 61-96 zeros; taxel IDs 60-95
1915  for (y = 60; y<=95; y++){
1916  bottleRightHand.addDouble(0.0);
1917  }
1918 
1919  //pam - positions 97-144 palm taxels; taxel IDs have index by one lower (inside these, IDs 107, 119, 131, and 139 are thermal pads ~ 0s);
1920  if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].indivTaxelResolution){
1921  for (y = 96; y<=143; y++){
1922  if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1923  bottleRightHand.addDouble(255.0);
1924  }
1925  else{
1926  bottleRightHand.addDouble(0.0);
1927  }
1928  }
1929  }
1930  else{ //we fill the whole palm
1931  for (int y = 96; y<=143; y++){
1932  bottleRightHand.addDouble(255.0); //we ignore the thermal pad positions, which should be 0s, for now
1933  }
1934  }
1935  //filling the rest: 145-192 zeros. IDs: 144-191
1936  for (int y = 144; y<=191; y++){
1937  bottleRightHand.addDouble(0.0);
1938  }
1939  }
1940  else{
1941  bottleRightHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1942  }
1943  robot_streamer->sendTouchRightHand(bottleRightHand);
1944  }
1945 
1946 
1947  if(robot_streamer->shouldSendTouchLeftArm()){
1948  Bottle bottleLeftArm;
1949  if (contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].coverTouched){
1950  if (contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].indivTaxelResolution){
1951  for (int y = 0; y<=767; y++){
1952  if (contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1953  bottleLeftArm.addDouble(255.0);
1954  }
1955  else{
1956  bottleLeftArm.addDouble(0.0);
1957  }
1958  }
1959  }
1960  else{ //we fill the whole upper arm
1961  bottleLeftArm = Bottle(odeinit._iCub->fullSkinActivationUpperArm);
1962  }
1963  }
1964  else{
1965  bottleLeftArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
1966  }
1967  robot_streamer->sendTouchLeftArm(bottleLeftArm);
1968  }
1969  if(robot_streamer->shouldSendTouchLeftForearm()){
1970  Bottle bottleLeftForearm;
1971  if (contactICubSkinEmulMap[SKIN_LEFT_FOREARM].coverTouched){
1972  if (contactICubSkinEmulMap[SKIN_LEFT_FOREARM].indivTaxelResolution){
1973  for (int y = 0; y<=383; y++){
1974  if (contactICubSkinEmulMap[SKIN_LEFT_FOREARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1975  bottleLeftForearm.addDouble(255.0);
1976  }
1977  else{
1978  bottleLeftForearm.addDouble(0.0);
1979  }
1980  }
1981  }
1982  else{ //we fill the whole forearm
1983  bottleLeftForearm = Bottle(odeinit._iCub->fullSkinActivationForearm);
1984  }
1985  }
1986  else{
1987  bottleLeftForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
1988  }
1989  robot_streamer->sendTouchLeftForearm(bottleLeftForearm);
1990  }
1991  if(robot_streamer->shouldSendTouchRightArm()){
1992  Bottle bottleRightArm;
1993  if (contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].coverTouched){
1994  if (contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].indivTaxelResolution){
1995  for (int y = 0; y<=767; y++){
1996  if (contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
1997  bottleRightArm.addDouble(255.0);
1998  }
1999  else{
2000  bottleRightArm.addDouble(0.0);
2001  }
2002  }
2003  }
2004  else{ //we fill the whole upper arm
2005  bottleRightArm = Bottle(odeinit._iCub->fullSkinActivationUpperArm);
2006  }
2007  }
2008  else{
2009  bottleRightArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
2010  }
2011  robot_streamer->sendTouchRightArm(bottleRightArm);
2012  }
2013  if(robot_streamer->shouldSendTouchRightForearm()){
2014  Bottle bottleRightForearm;
2015  if (contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].coverTouched){
2016  if (contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].indivTaxelResolution){
2017  for (int y = 0; y<=383; y++){
2018  if (contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
2019  bottleRightForearm.addDouble(255.0);
2020  }
2021  else{
2022  bottleRightForearm.addDouble(0.0);
2023  }
2024  }
2025  }
2026  else{ //we fill the whole forearm
2027  bottleRightForearm = Bottle(odeinit._iCub->fullSkinActivationForearm);
2028  }
2029  }
2030  else{
2031  bottleRightForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
2032  }
2033  robot_streamer->sendTouchRightForearm(bottleRightForearm);
2034  }
2035  if(robot_streamer->shouldSendTouchTorso()){
2036  Bottle bottleTorso;
2037  if (contactICubSkinEmulMap[SKIN_FRONT_TORSO].coverTouched){
2038  if (contactICubSkinEmulMap[SKIN_FRONT_TORSO].indivTaxelResolution){
2039  for (int y = 0; y<=767; y++){
2040  if (contactICubSkinEmulMap[SKIN_FRONT_TORSO].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1
2041  bottleTorso.addDouble(255.0);
2042  }
2043  else{
2044  bottleTorso.addDouble(0.0);
2045  }
2046  }
2047  }
2048  else{ //we fill the whole torso
2049  bottleTorso = Bottle(odeinit._iCub->fullSkinActivationTorso);
2050  }
2051  }
2052  else{
2053  bottleTorso = Bottle(odeinit._iCub->emptySkinActivationTorso);
2054  }
2055  robot_streamer->sendTouchTorso(bottleTorso);
2056  }
2057 }
2058 
2059 
2060 void OdeSdlSimulation::mapPositionIntoTaxelList(const SkinPart skin_part,const Vector geo_center_link_FoR,std::vector<unsigned int>& list_of_taxels){
2061 
2062  switch (skin_part){
2063  case SKIN_LEFT_HAND:
2064  if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.012) && (geo_center_link_FoR[1]>-0.026) && (geo_center_link_FoR[1]<-0.0055)){
2065  list_of_taxels.push_back(121);list_of_taxels.push_back(122);list_of_taxels.push_back(123);
2066  list_of_taxels.push_back(124);list_of_taxels.push_back(125);list_of_taxels.push_back(126);
2067  list_of_taxels.push_back(127);list_of_taxels.push_back(128);
2068  //list_of_taxels.push_back();list_of_taxels.push_back();list_of_taxels.push_back();
2069  }
2070  else if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.012) && (geo_center_link_FoR[1]>-0.0055) && (geo_center_link_FoR[1]<0.01)){
2071  list_of_taxels.push_back(96);list_of_taxels.push_back(97);list_of_taxels.push_back(98);
2072  list_of_taxels.push_back(99);list_of_taxels.push_back(102);list_of_taxels.push_back(103);
2073  list_of_taxels.push_back(120);list_of_taxels.push_back(129);list_of_taxels.push_back(130);
2074  }
2075  else if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.014) && (geo_center_link_FoR[1]>0.01) && (geo_center_link_FoR[1]<0.03) ){
2076  list_of_taxels.push_back(100);list_of_taxels.push_back(101);list_of_taxels.push_back(104);
2077  list_of_taxels.push_back(105);list_of_taxels.push_back(106);list_of_taxels.push_back(113);
2078  list_of_taxels.push_back(116);list_of_taxels.push_back(117);
2079  }
2080  else if ((geo_center_link_FoR[0]<-0.014) && (geo_center_link_FoR[0]>-0.024) && (geo_center_link_FoR[1]>0.0) && (geo_center_link_FoR[1]<0.03) ){
2081  list_of_taxels.push_back(108);list_of_taxels.push_back(109);list_of_taxels.push_back(110);
2082  list_of_taxels.push_back(111);list_of_taxels.push_back(112);list_of_taxels.push_back(114);
2083  list_of_taxels.push_back(115);list_of_taxels.push_back(118); list_of_taxels.push_back(142);
2084  list_of_taxels.push_back(143);
2085  }
2086  else if ((geo_center_link_FoR[0]<-0.024) && (geo_center_link_FoR[0]>-0.04) && (geo_center_link_FoR[1]>0.0) && (geo_center_link_FoR[1]<0.03) ){
2087  list_of_taxels.push_back(132);list_of_taxels.push_back(133);list_of_taxels.push_back(134);
2088  list_of_taxels.push_back(135);list_of_taxels.push_back(136);list_of_taxels.push_back(137);
2089  list_of_taxels.push_back(138);list_of_taxels.push_back(140); list_of_taxels.push_back(141);
2090  }
2091  else{
2092  printf("OdeSdlSimulation::mapPositionIntoTaxelList: WARNING: contact at part: %d, coordinates: %f %f %f, but no taxels asigned to this position. \n",skin_part,geo_center_link_FoR[0],geo_center_link_FoR[1],geo_center_link_FoR[2]);
2093  }
2094  break;
2095  case SKIN_RIGHT_HAND:
2096  if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.012) && (geo_center_link_FoR[1]>-0.026) && (geo_center_link_FoR[1]<-0.0055)){
2097  list_of_taxels.push_back(120);list_of_taxels.push_back(121);list_of_taxels.push_back(122);
2098  list_of_taxels.push_back(123);list_of_taxels.push_back(124);list_of_taxels.push_back(125);
2099  list_of_taxels.push_back(126);list_of_taxels.push_back(128);
2100  //list_of_taxels.push_back();list_of_taxels.push_back();list_of_taxels.push_back();
2101  }
2102  else if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.012) && (geo_center_link_FoR[1]>-0.0055) && (geo_center_link_FoR[1]<0.01)){
2103  list_of_taxels.push_back(99);list_of_taxels.push_back(102);list_of_taxels.push_back(103);
2104  list_of_taxels.push_back(104);list_of_taxels.push_back(105);list_of_taxels.push_back(106);
2105  list_of_taxels.push_back(127);list_of_taxels.push_back(129);list_of_taxels.push_back(130);
2106  }
2107  else if ((geo_center_link_FoR[0]<0.003) && (geo_center_link_FoR[0]>-0.014) && (geo_center_link_FoR[1]>0.01) && (geo_center_link_FoR[1]<0.03) ){
2108  list_of_taxels.push_back(96);list_of_taxels.push_back(97);list_of_taxels.push_back(98);
2109  list_of_taxels.push_back(100);list_of_taxels.push_back(101);list_of_taxels.push_back(110);
2110  list_of_taxels.push_back(111);list_of_taxels.push_back(112);
2111  }
2112  else if ((geo_center_link_FoR[0]<-0.014) && (geo_center_link_FoR[0]>-0.024) && (geo_center_link_FoR[1]>0.0) && (geo_center_link_FoR[1]<0.03) ){
2113  list_of_taxels.push_back(108);list_of_taxels.push_back(109);list_of_taxels.push_back(113);
2114  list_of_taxels.push_back(114);list_of_taxels.push_back(115);list_of_taxels.push_back(116);
2115  list_of_taxels.push_back(117);list_of_taxels.push_back(118); list_of_taxels.push_back(142);
2116  list_of_taxels.push_back(143);
2117  }
2118  else if ((geo_center_link_FoR[0]<-0.024) && (geo_center_link_FoR[0]>-0.040) && (geo_center_link_FoR[1]>0.0) && (geo_center_link_FoR[1]<0.03) ){
2119  list_of_taxels.push_back(132);list_of_taxels.push_back(133);list_of_taxels.push_back(134);
2120  list_of_taxels.push_back(135);list_of_taxels.push_back(136);list_of_taxels.push_back(137);
2121  list_of_taxels.push_back(138);list_of_taxels.push_back(140); list_of_taxels.push_back(141);
2122  }
2123  else{
2124  printf("OdeSdlSimulation::mapPositionIntoTaxelList: WARNING: contact at part: %d, coordinates: %f %f %f, but no taxels asigned to this position. \n",skin_part,geo_center_link_FoR[0],geo_center_link_FoR[1],geo_center_link_FoR[2]);
2125  }
2126  break;
2127  default:
2128  printf("OdeSdlSimulation::mapPositionIntoTaxelList: WARNING: contact at part: %d, but no taxel resolution implemented for this skin part. \n",skin_part);
2129  }
2130 
2131 // if (odeinit.verbosity > 2) {
2132 // printf("OdeSdlSimulation::mapPositionIntoTaxelList: contact at part: %d, coordinates: %f %f %f. \n",skin_part,geo_center_link_FoR[0],geo_center_link_FoR[1],geo_center_link_FoR[2]);
2133 // printf(" Taxel list: ");
2134 // for (std::vector<unsigned int>::const_iterator it = list_of_taxels.begin() ; it != list_of_taxels.end(); ++it){
2135 // printf("%d,",*it);
2136 // }
2137 // printf("\n");
2138 // }
2139  return;
2140 }
2141 
2142 void OdeSdlSimulation::mapFingertipIntoTaxelList(const HandPart hand_part,std::vector<unsigned int>& list_of_taxels)
2143 {
2144  int i=0;
2145  switch(hand_part)
2146  {
2147  case INDEX:
2148  for(i=0; i<=11; i++){
2149  list_of_taxels.push_back(i);
2150  }
2151  break;
2152  case MIDDLE:
2153  for(i=12; i<=23; i++){
2154  list_of_taxels.push_back(i);
2155  }
2156  break;
2157  case RING:
2158  for(i=24; i<=35; i++){
2159  list_of_taxels.push_back(i);
2160  }
2161  break;
2162  case LITTLE:
2163  for(i=36; i<=47; i++){
2164  list_of_taxels.push_back(i);
2165  }
2166  break;
2167  case THUMB:
2168  for(i=48; i<=59; i++){
2169  list_of_taxels.push_back(i);
2170  }
2171  break;
2172  default:
2173  printf("Warning: OdeSdlSimulation::mapFingertipIntoTaxelList: unexpected HandPart: %d. Pushing fake taxel ID \n",hand_part);
2174  list_of_taxels.push_back(FAKE_TAXEL_ID);
2175 
2176  }
2177 
2178 
2179 }
2180 
2181 //Auxiliary function to print class of geom - according to section 9.5 of ODE manual
2182 std::string OdeSdlSimulation::getGeomClassName(const int geom_class,std::string & s)
2183 {
2184  switch(geom_class){
2185  case 0:
2186  s = "sphere";
2187  break;
2188  case 1:
2189  s = "box";
2190  break;
2191  case 2:
2192  s = "capsule";
2193  break;
2194  case 3:
2195  s = "cylinder";
2196  break;
2197  case 4:
2198  s = "plane";
2199  break;
2200  case 8:
2201  s= "triangle mesh";
2202  break;
2203  case 10:
2204  case 11:
2205  s = "simple space";
2206  break;
2207  case 12:
2208  s="hash space";
2209  break;
2210  default:
2211  s ="unknown type";
2212  break;
2213  }
2214  return s;
2215 
2216 }
static float hpr[8]
Definition: iCub_Sim.cpp:48
static float lasty
Definition: iCub_Sim.cpp:76
const Skin_2_Link SkinPart_2_LinkNum[SKIN_PART_SIZE]
Definition: common.h:117
static int mouseDiffy
Definition: iCub_Sim.cpp:52
static bool eyeCams
Definition: iCub_Sim.cpp:88
static SDL_Surface * image
Definition: iCub_Sim.cpp:83
#define MAX_PART
iCub::iKin::iCubInertialSensor iKinInertialSensor
Definition: iCub.h:272
virtual bool getTrqData(Bottle data)
Definition: iCub_Sim.cpp:1600
struct timeval prevTime[BOARD_NUM]
virtual bool shouldSendInertial()=0
static RobotConfig * robot_config
Definition: iCub_Sim.cpp:87
double checkTouchSensor_continuousValued(int bodyToCheck)
Definition: iCub.cpp:108
yarp::os::Semaphore mutex
Definition: OdeInit.h:64
yarp::os::Semaphore mutexTexture
Definition: OdeInit.h:65
static float * VAD
Definition: iCub_Sim.cpp:63
static int width_left
Definition: iCub_Sim.cpp:92
virtual void sendTouchRightHand(yarp::os::Bottle &report)=0
static int mouse1_down_y
Definition: iCub_Sim.cpp:60
#define PART_ARM_RIGHT
Class representing a list of external contacts acting on the iCub' skin.
virtual void sendTouchLeftForearm(yarp::os::Bottle &report)=0
static double duration
Definition: iCub_Sim.cpp:79
bool sync
Definition: OdeInit.h:69
dSpaceID body_geom_space_id
Definition: OdeInit.h:78
iCub::iKin::iCubArm iKinRightArm
Definition: iCub.h:271
dBodyID inertialBody
Definition: iCub.h:96
static dJointFeedback touchSensorFeedbacks[MAX_DJOINT_FEEDBACKSTRUCTS]
Definition: iCub_Sim.cpp:118
OdeSdlSimulation()
Constructor.
Definition: iCub_Sim.cpp:1381
void DrawVideo(VideoTexture *video)
Definition: rendering.cpp:455
virtual void sendInertial(yarp::os::Bottle &report)=0
int verbosity
Definition: OdeInit.h:71
virtual void sendSkinEvents(iCub::skinDynLib::skinContactList &skinContactListReport)=0
#define LEFT_ARM
void DrawGround(bool wireframe)
Definition: rendering.cpp:121
string eyeLidsPortName
Definition: iCub.h:86
int MODEL_NUM
Definition: world.h:174
static long startTime
Definition: iCub_Sim.cpp:78
virtual void checkTorques()=0
void getSkinAndBodyPartFromSpaceAndGeomID(const dSpaceID geomSpaceID, const dGeomID geomID, SkinPart &skinPart, BodyPart &bodyPart, HandPart &handPart, bool &skinCoverFlag, bool &fingertipFlag)
Definition: iCub.cpp:4215
bool WAITLOADING
Definition: world.h:223
#define PART_ARM_LEFT
bool static_model
Definition: world.h:224
static const GLfloat light_position[]
Definition: iCub_Sim.cpp:89
static int height_right
Definition: iCub_Sim.cpp:95
dSpaceID iCubRightArmSpace
Definition: iCub.h:89
static double dstep
Definition: iCub_Sim.cpp:39
ICubSim * _iCub
Definition: OdeInit.h:66
static float zoom
Definition: iCub_Sim.cpp:74
static VideoTexture * video
Definition: iCub_Sim.cpp:85
virtual bool shouldSendTouchLeftForearm()=0
static long ode_step_length
Definition: iCub_Sim.cpp:38
void setName(string module)
dBodyID l_hand
Definition: iCub.h:163
const dReal * pos
Definition: iCub_Sim.cpp:65
static float view2_hpr[3]
Definition: iCub_Sim.cpp:73
dSpaceID iCubLeftArmSpace
Definition: iCub.h:89
static int stop
Definition: iCub_Sim.cpp:44
dBodyID r_hand
Definition: iCub.h:163
static float ydistance
Definition: iCub_Sim.cpp:68
zeros(2, 2) eye(2
string getName()
Definition: OdeInit.h:89
dWorldID world
Definition: OdeInit.h:57
static float ypos
Definition: iCub_Sim.cpp:75
Matrix H_r2w
Definition: iCub.h:284
static float angle
Definition: iCub_Sim.cpp:75
ConstString actSkinEmul
Definition: iCub.h:80
std::set< unsigned int > taxelsTouched
Definition: iCub_Sim.cpp:105
bool add(const char *port, int textureIndex)
Definition: VideoTexture.h:78
static float yrot
Definition: iCub_Sim.cpp:75
static float zrot
Definition: iCub_Sim.cpp:75
static RobotStreamer * robot_streamer
Definition: iCub_Sim.cpp:86
yarp::os::ConstString texture
Definition: world.h:295
static int cameraSizeWidth
Definition: iCub_Sim.cpp:99
static double frames
Definition: iCub_Sim.cpp:79
Semaphore ODE_access(1)
list< contactOnSkin_t > listOfSkinContactInfos
Definition: OdeInit.h:83
#define MAX_DJOINT_FEEDBACKSTRUCTS
Definition: iCub_Sim.cpp:116
int modelTexture[100]
Definition: world.h:261
virtual bool shouldSendTouchLeftArm()=0
static int width
Definition: iCub_Sim.cpp:56
static float view_xyz[3]
Definition: iCub_Sim.cpp:70
bool reinitialized
Definition: iCub.h:84
tuple config
Definition: icubapp.py:262
virtual yarp::os::ResourceFinder & getFinder()=0
static float yrotrad
Definition: iCub_Sim.cpp:77
ConstString actVision
Definition: iCub.h:80
virtual bool shouldSendTouchTorso()=0
#define MAX_CONTACTS
Definition: iCub.h:68
dSpaceID iCubHeadSpace
Definition: iCub.h:89
void drawView(bool left, bool right, bool wide)
Render the requested view.
Definition: iCub_Sim.cpp:1309
tuple name
Definition: manager.py:710
Definition: main.cpp:145
Bottle fullSkinActivationUpperArm
Definition: iCub.h:280
dSpaceID space
Definition: OdeInit.h:58
static float xrot
Definition: iCub_Sim.cpp:75
iCubSimulationControl ** _controls
Definition: OdeInit.h:73
virtual void sendTouchTorso(yarp::os::Bottle &report)=0
virtual bool shouldSendSkinEvents()=0
static double seconds
Definition: iCub_Sim.cpp:79
yarp::sig::Matrix getH(const unsigned int i, const bool allLink=false)
Returns the rigid roto-translation matrix from the root reference frame to the ith frame in Denavit-H...
Definition: iKinFwd.cpp:752
fprintf(fid,'\n')
static float view2_xyz[3]
Definition: iCub_Sim.cpp:72
dSpaceID iCubLegsSpace
Definition: iCub.h:89
static int v
Definition: iCub_Sim.cpp:45
static float xrotrad
Definition: iCub_Sim.cpp:77
void sendHomePos()
Definition: OdeInit.cpp:126
static OdeInit & get()
Definition: OdeInit.cpp:163
virtual void sendTouchRightForearm(yarp::os::Bottle &report)=0
static bool picking
Definition: iCub_Sim.cpp:53
static long gl_frame_length
Definition: iCub_Sim.cpp:37
Bottle fullSkinActivationForearm
Definition: iCub.h:279
static long finishTime
Definition: iCub_Sim.cpp:78
static const int TORSO_DOF
Definition: common.h:194
static int height
Definition: iCub_Sim.cpp:57
dJointID contact_joint
Definition: OdeInit.h:81
Bottle emptySkinActivationForearm
Definition: iCub.h:276
static bool extractImages
Definition: iCub_Sim.cpp:84
virtual int getWorldTimestep()=0
static int mouse0_down_x
Definition: iCub_Sim.cpp:59
This file is responsible for the initialisation of the world parameters that are controlled by ODE...
for j
ConstString actSelfCol
Definition: iCub.h:80
ODE state information.
Definition: OdeInit.h:54
virtual bool shouldSendTouchRightHand()=0
int s_modelTexture[100]
Definition: world.h:262
#define M_PI
Definition: math.h:53
static int nFeedbackStructs
Definition: iCub_Sim.cpp:119
static float lastx
Definition: iCub_Sim.cpp:76
virtual bool getImage(yarp::sig::ImageOf< yarp::sig::PixelRgb > &target)
Definition: iCub_Sim.cpp:1611
ConstString actTorso
Definition: iCub.h:80
static double FPS
Definition: iCub_Sim.cpp:79
static float zpos
Definition: iCub_Sim.cpp:75
static int mouse0_down_y
Definition: iCub_Sim.cpp:60
Bottle emptySkinActivationHand
Definition: iCub.h:275
void draw()
Definition: world.cpp:62
#define CTRL_RAD2DEG
Definition: iCub_Sim.cpp:32
Bottle emptySkinActivationUpperArm
Definition: iCub.h:277
void clearBuffer()
Signal that we're done with a view.
Definition: iCub_Sim.cpp:1377
dGeomID inertialGeom
Definition: iCub.h:97
static float test[3]
Definition: iCub_Sim.cpp:80
double torqueData[100]
Definition: iCub.h:237
void simLoop(int h, int w)
Run the simulation.
Definition: iCub_Sim.cpp:1210
static Uint32 colorkey
Definition: iCub_Sim.cpp:82
static float xpos
Definition: iCub_Sim.cpp:75
virtual void sendTouchLeftHand(yarp::os::Bottle &report)=0
static float xdistance
Definition: iCub_Sim.cpp:69
static bool simrun
Definition: iCub_Sim.cpp:42
float eyeLidRot
Definition: iCub.h:85
dBodyID body[50]
Definition: iCub.h:117
dJointGroupID contactgroup
Definition: OdeInit.h:59
static float angle_xref
Definition: iCub_Sim.cpp:66
dContactGeom contact_geom
Definition: OdeInit.h:80
static int contactPoint
Definition: iCub_Sim.cpp:51
void setJointControlAction()
Set the control action for all the joints, that can be either a velocity command or a torque command...
Definition: iCub.cpp:192
dGeomID Leye1_geom
Definition: iCub.h:177
~OdeSdlSimulation()
Destructor.
Definition: iCub_Sim.cpp:1586
static float view_hpr[3]
Definition: iCub_Sim.cpp:71
void drawSkyDome(float x, float y, float z, float width, float height, float length)
Definition: rendering.cpp:158
dGeomID Reye1_geom
Definition: iCub.h:182
worldSim * _wrld
Definition: OdeInit.h:67
void loadTexture(yarp::os::ConstString texture, int numTexture)
Definition: world.cpp:172
virtual bool shouldSendTouchRightForearm()=0
#define RIGHT_ARM
static float * VAD2
Definition: iCub_Sim.cpp:64
static bool glrun
Definition: iCub_Sim.cpp:41
ConstString actRArm
Definition: iCub.h:80
ConstString actStartHomePos
Definition: iCub.h:80
static double fov_right
Definition: iCub_Sim.cpp:97
ConstString actPressure
Definition: iCub.h:80
int s_MODEL_NUM
Definition: world.h:175
virtual bool getEncodersRaw(double *encs)
static double TimestepManager
Definition: iCub_Sim.cpp:79
dSpaceID iCub
Definition: iCub.h:88
bool checkSync(bool reset=false)
Definition: iCub_Sim.cpp:1591
bool stop
Definition: OdeInit.h:68
static int width_right
Definition: iCub_Sim.cpp:93
virtual bool shouldSendTouchLeftHand()=0
static int mouse_ray_x
Definition: iCub_Sim.cpp:61
Class representing an external contact acting on the iCub' skin.
Definition: skinContact.h:49
iCub::iKin::iCubArm iKinLeftArm
Definition: iCub.h:271
double SimTime
Definition: OdeInit.h:56
#define PART_TORSO
static int height_left
Definition: iCub_Sim.cpp:94
static int mouse_ray_y
Definition: iCub_Sim.cpp:62
static int mouse1_down_x
Definition: iCub_Sim.cpp:59
static int cameraSizeHeight
Definition: iCub_Sim.cpp:100
#define PART_HEAD
dBodyID lhandfingers3
Definition: iCub.h:133
#define FAKE_TAXEL_ID
Definition: iCub_Sim.h:61
virtual void sendTouchLeftArm(yarp::os::Bottle &report)=0
ConstString actHead
Definition: iCub.h:80
virtual bool shouldSendTouchRightArm()=0
form input data form the output data fill the input data for i
Definition: acquireData.m:52
std::map< dSpaceID, string > dSpaceNames
Definition: iCub.h:91
This class controls the simulation speed using dWorldstep for "exact" calculations, the collisions between objects/spaces and the rendering functions.
static double fov_left
Definition: iCub_Sim.cpp:96
int getLinkNum(SkinPart s)
Get the link number associated to the specified skin part.
Definition: common.cpp:83
ConstString actRHand
Definition: iCub.h:80
void draw()
Definition: iCub.cpp:318
static float angle_yref
Definition: iCub_Sim.cpp:67
static float xyz[3]
Definition: iCub_Sim.cpp:47
static float cam_rx
Definition: iCub_Sim.cpp:54
static std::map< SkinPart, contactICubSkinEmul_t > contactICubSkinEmulMap
Definition: iCub_Sim.cpp:108
bool setup_opengl(ResourceFinder &finder)
Definition: rendering.cpp:63
Bottle fullSkinActivationTorso
Definition: iCub.h:281
void init(RobotStreamer *streamer, RobotConfig *config)
Initialization.
Definition: iCub_Sim.cpp:1384
std::map< dGeomID, string > dGeomNames
Definition: iCub.h:92
static float cam_ry
Definition: iCub_Sim.cpp:54
ConstString actLArm
Definition: iCub.h:80
static bool START_SELF_COLLISION_DETECTION
Definition: iCub_Sim.cpp:121
yarp::sig::Vector setAng(const yarp::sig::Vector &q)
Sets the free joint angles to values of q[i].
static void sighandler(int)
Definition: main.cpp:152
static int mouseDiffx
Definition: iCub_Sim.cpp:52
ConstString actLHand
Definition: iCub.h:80
dBodyID rhandfingers3
Definition: iCub.h:145
virtual void sendTouchRightArm(yarp::os::Bottle &report)=0
bool checkTouchSensor(int bodyToCheck)
Definition: iCub.cpp:142
virtual void sendVision()=0
Bottle emptySkinActivationTorso
Definition: iCub.h:278
static float rez[3]
Definition: iCub_Sim.cpp:49
dSpaceID iCubTorsoSpace
Definition: iCub.h:89