iCub-main
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
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 
25 using namespace yarp::sig;
26 
27 // globals
28 Semaphore ODE_access(1);
29 #define CTRL_RAD2DEG (180.0/M_PI)
30 #define CTRL_DEG2RAD (M_PI/180.0)
31 
32 // locals
33 // NOTE that we use (long) instead of (clock_t), because on MacOS, (clock_t) is unsigned, while we need negative numbers
34 static long gl_frame_length = 1000/30; // update opengl and vision stream at 30 Hz
35 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)
36 static double dstep = 10.0/1000.0; // step size in ODE's dWorldStep in seconds
37 
38 static bool glrun; // draw gl
39 static bool simrun; // run simulator thread
40 
41 static int stop = 0;
42 static int v = 0;
43 
44 static float xyz[3];
45 static float hpr[8];
46 static float rez[3];
47 
48 static int contactPoint;
49 static int mouseDiffx, mouseDiffy;
50 static bool picking = false;
51 static float cam_rx = 0.0, cam_ry = 0.0;
52 
53 static int width = 640;
54 static int height = 480;
55 
58 static int mouse_ray_x;
59 static int mouse_ray_y;
60 static float *VAD;
61 static float *VAD2;
62 const dReal *pos;
63 static float angle_xref = 0.0f;
64 static float angle_yref = 25.0f;
65 static float ydistance = 10.0f;
66 static float xdistance = 0.0f;
67 static float view_xyz[3]; // position x,y,z
68 static float view_hpr[3]; // heading, pitch, roll (degrees)
69 static float view2_xyz[3];
70 static float view2_hpr[3];
71 static float zoom = 0;
72 static float xpos = 0, ypos = 0, zpos = 0, xrot = 0, yrot = 0, zrot = 0, angle=0.0;
73 static float lastx, lasty;
74 static float xrotrad = 0, yrotrad = 0;
75 static long startTime, finishTime;
77 static float test[3];
78 //static SDL_TimerID id;
79 static Uint32 colorkey;
80 static SDL_Surface *image;
81 static bool extractImages = false;
82 static VideoTexture *video = NULL;
83 static RobotStreamer *robot_streamer = NULL;
84 static RobotConfig *robot_config = NULL;
85 static bool eyeCams;
86 static const GLfloat light_position[] = { 0.0f, 5.0f, 5.0f, 0.0f };
87 
88 //camera calibration parameters
89 static int width_left;
90 static int width_right;
91 static int height_left;
92 static int height_right;
93 static double fov_left;
94 static double fov_right;
95 
96 
97 static int cameraSizeWidth;
98 static int cameraSizeHeight;
99 
100 
101 /* 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.
102  * The number of collisions and contact joints may vary, but we allocate these as a static array for performance issues.
103  * (Allocating feedback structs at every simulation step would degrade simulation performance).
104  * If the MAX_DJOINT_FEEDBACKSTRUCTS was exceeded, contacts will still be saved for the purposes of whole_body_skin_emul,
105  * but the forces send to skinEvents will not be available.
106 */
107 #define MAX_DJOINT_FEEDBACKSTRUCTS 500
108 
110 static int nFeedbackStructs=0;
111 
112 static bool START_SELF_COLLISION_DETECTION = false; //we want to set this trigger on only after the robot is in in home pos -
113  //it's initial configuration is with arms inside the thighs
114 
115 
116 void OdeSdlSimulation::draw() {
117  OdeInit& odeinit = OdeInit::get();
118  odeinit._iCub->draw();
119  odeinit._wrld->draw();
120 }
121 
122 void OdeSdlSimulation::printStats() {
123  OdeInit& odeinit = OdeInit::get();
124 
125  finishTime = (long) clock() ;
126  duration += (double)(finishTime - startTime) / CLOCKS_PER_SEC ;
127  frames ++ ;
128  FPS = frames / duration ;
129  startTime = (long) clock() ;
130  odeinit.SimTime = duration;
131  //printf("duration: %.2lf\n",odeinit.SimTime);
132  static double starting_time_stamp = 0;
133  //test[0] = dBodyGetPosition(odeinit._iCub->body_cube[0])[0];
134  //test[1] = dBodyGetPosition(odeinit._iCub->body_cube[0])[1];
135  //test[2] = dBodyGetPosition(odeinit._iCub->body_cube[0])[2];
136  //printf("test[0] %f test[1] %f test[2] %f\n",test[0],test[1],test[2]);
137  if( duration - starting_time_stamp >= 1){
138  //printf("Frames: %.2lf Duration: %.2lf fps: %3.1f \n",frames,duration,FPS);
139  starting_time_stamp = duration;
140  }
141  //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]);
142  //drawText(text, textPos);
143 }
144 
145 void OdeSdlSimulation::handle_key_down(SDL_keysym* keysym) {
146  switch (keysym->sym)
147  {
148  case SDLK_e:
149  break;
150  case SDLK_r:
151  initViewpoint();
152  break;
153  case SDLK_t:
154  break;
155  case SDLK_y:
156  break;
157  case SDLK_SPACE:
158  printf("SPACEBAR pressed! Press spacebar again to disable/enable drawing.\n");
159  glrun = !glrun;
160  break;
161  default:
162  break;
163  }
164 }
165 
166 void OdeSdlSimulation::handle_mouse_motion(SDL_MouseMotionEvent* mousemotion) {
167  if (SDL_GetMouseState(NULL, NULL) & SDL_BUTTON(1)){// MOUSE LEFT BUTTON
168  //if (!picking){
169  //camera movement
170  angle_xref += (float)mousemotion->xrel; // 10.0f;
171  angle_yref += (float)mousemotion->yrel; // 10.0f;
172  mouseMovement(angle_xref,angle_yref);
173 
174  if (v<1){
175  //mouse_ray_x = mouse0_down_x;
176  //mouse_ray_y = mouse0_down_y;
177  }
178  /*mouseDiffx = mouse0_down_x - mouse_ray_x;
179  mouseDiffy = mouse0_down_y - mouse_ray_y;
180  mouse_ray_x = mouse0_down_x;
181  mouse_ray_y = mouse0_down_y;*/
182 
183  //VAD = ScreenToWorld(mouse0_down_x,mouse0_down_y,0);
184  //xpos = VAD[0];ypos = VAD[1];zpos = VAD[2];
185  //VAD2 =ScreenToWorld(mouse0_down_x,mouse0_down_y,1);
186  //xpos2 = VAD2[0];ypos2 = VAD2[1];zpos2 = VAD2[2];
187 
188  //if (i<1){ray = dCreateRay(space,100*100);}
189  //Origin[0] = xpos;
190  //Origin[1] = ypos;
191  //Origin[2] = zpos;
192  //Origin[3] = 0;
193  //Direction[0] = xpos2;
194  //Direction[1] = ypos2;
195  //Direction[2] = zpos2;
196  //Direction[3] = 0;
197  //dGeomRaySet(ray, Origin[0], Origin[1], Origin[2], Direction[0], Direction[1], Direction[2]);
198  //dGeomSetPosition(ray, xpos,ypos,zpos);
199  //i++;
200  }
201  if (SDL_GetMouseState(NULL, NULL) & SDL_BUTTON(3)){// MOUSE RIGHT BUTTON
202 
203  //xdistance -= mousemotion->xrel / 10.0f;
204  //ydistance -= mousemotion->yrel / 10.0f;
205  }
206 }
207 
208 void OdeSdlSimulation::process_events(void) {
209  OdeInit& odeinit = OdeInit::get();
210  SDL_Event event;
211 
212  Uint8 * keystate = SDL_GetKeyState(NULL);
213  if(keystate[SDLK_q]){xrot += 1 * 0.4f;if (xrot >360) xrot -= 360 * 0.1f;}
214  if(keystate[SDLK_z]){xrot -= 1 * 0.4f;if (xrot < -360) xrot += 360 * 0.1f;}
215  if(keystate[SDLK_w]){yrotrad = (yrot / 180 * 3.141592654f); xrotrad = (xrot / 180 * 3.141592654f);
216  xpos += float(sin(yrotrad))* 0.005f; ;zpos -= float(cos(yrotrad))* 0.005f; ypos -= float(sin(xrotrad))* 0.005f;}
217  if(keystate[SDLK_s]){yrotrad = (yrot / 180 * 3.141592654f); xrotrad = (xrot / 180 * 3.141592654f);
218  xpos -= float(sin(yrotrad))* 0.005f;zpos += float(cos(yrotrad))* 0.005f; ;ypos += float(sin(xrotrad))* 0.005f;}
219  if (keystate[SDLK_a]){yrotrad = (yrot / 180 * 3.141592654f);xpos -= float(cos(yrotrad)) * 0.008;zpos -= float(sin(yrotrad)) * 0.008; }
220  if (keystate[SDLK_d]){yrotrad = (yrot / 180 * 3.141592654f);xpos += float(cos(yrotrad)) * 0.008;zpos += float(sin(yrotrad)) * 0.008;}
221  if(keystate[SDLK_e]){zrot += 1 * 0.4f;if (zrot >360) zrot -= 360 * 0.4f;}
222  if(keystate[SDLK_c]){zrot -= 1 * 0.4f;if (zrot < -360) zrot += 360 * 0.4f;}
223 
224  if (keystate[SDLK_f]){ypos +=1 *0.005f;}
225  if (keystate[SDLK_v]){ypos -=1 *0.005f;}
226 
227  if(keystate[SDLK_1]){initViewpoint();}
228 
229  if (keystate[SDLK_5]){
230 
231  if ((odeinit._iCub->eyeLidRot) < 0.55) odeinit._iCub->eyeLidRot += 0.01;
232  cout<<odeinit._iCub->eyeLidRot<<endl;
233  }
234  if (keystate[SDLK_6]){
235  if ((odeinit._iCub->eyeLidRot) > 0.01) odeinit._iCub->eyeLidRot -= 0.01;
236  cout<<odeinit._iCub->eyeLidRot<<endl;
237  }
238  if (keystate[SDLK_h])
239  {
240  odeinit.sendHomePos();
241  }
242  /* Grab all the events off the queue. */
243  while (SDL_PollEvent(&event)){
244  switch (event.type)
245  {
246  case SDL_VIDEORESIZE:
247  width = event.resize.w;
248  height = event.resize.h;
249  SDL_SetVideoMode(width,height,16,SDL_OPENGL | SDL_RESIZABLE);
250  {
251  bool ok = setup_opengl(robot_config->getFinder());
252  if (!ok) {
253  odeinit.stop = true;
254  }
255  }
256  odeinit._iCub->reinitialized = true;
257  //draw_screen( );
258  break;
259  case SDL_KEYDOWN:
260  /* Handle key presses*/
261  handle_key_down(&event.key.keysym);
262  // SDL_GetKeyName(event.key.keysym.sym));
263  break;
264  break;
265  case SDL_MOUSEMOTION:
266  handle_mouse_motion(&event.motion);
267  mouse0_down_x = event.button.x;
268  mouse0_down_y = event.button.y;
269  break;
270  case SDL_QUIT:
271  /* Handle quit requests (like Ctrl-c). */
272  odeinit.stop = true;
273  break;
274 
275  case SDL_MOUSEBUTTONDOWN:
276  handle_mouse_motion(&event.motion);
277  switch (event.button.button)
278  {
279  case SDL_BUTTON_LEFT:
280  //deleteRay = false;
281  picking = false;
282  //printf(" Down\n");
283  break;
284  case SDL_BUTTON_MIDDLE:
285  break;
286  case SDL_BUTTON_RIGHT:
287  break;
288  default:
289  //this is not reached
290  break;
291  }
292  break;
293  break;
294  case SDL_MOUSEBUTTONUP:
295  switch (event.button.button)
296  {
297  case SDL_BUTTON_LEFT:
298  //printf(" up\n");
299  v=0;
300  break;
301  case SDL_BUTTON_MIDDLE:
302  //nothing
303  break;
304  case SDL_BUTTON_RIGHT:
305  //nothing
306  break;
307  default:
308  //this is not reached either
309  break;
310  }
311  break;
312  }
313  }
314 }
315 
316 void OdeSdlSimulation::nearCallback (void *data, dGeomID o1, dGeomID o2) {
317 
318  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),
319  //the contacts generated between the robot and the ground that are always present can be ignored
320 
321  OdeInit& odeinit = OdeInit::get();
322 
323  assert(o1);
324  assert(o2);
325 
326  dSpaceID space1,space2;
327  dSpaceID superSpace1,superSpace2;
328  std::string geom1className("");
329  std::string geom2ClassName("");
330  std::string geom1name("");
331  std::string geom2name("");
332  bool geom1isiCubPart = false;
333  bool geom2isiCubPart = false;
334  bool geom1isTorsoOrArm = false;
335  bool geom2isTorsoOrArm = false;
336  int subLevel1;
337  //determine the indentation level for the printouts based on the sublevel in the hiearchy of spaces
338  string indentString("");
339  std::map<dGeomID,string>::iterator geom1namesIt;
340  std::map<dGeomID,string>::iterator geom2namesIt;
341 
342  if (dGeomIsSpace(o1)){
343  space1 = (dSpaceID)o1;
344  } else {
345  space1 = dGeomGetSpace(o1);
346  indentString = indentString + " --- "; //extra indentation level because it is a geom in that space
347  }
348  subLevel1 = dSpaceGetSublevel(space1);
349  for (int i=1;i<=subLevel1;i++){ //start from i=1, for sublevel==0 we don't add any indentation
350  indentString = indentString + " --- ";
351  }
352 
353  if (MY_VERBOSITY > 2) printf("%s nearCallback()\n",indentString.c_str());
354 
355  if (dGeomIsSpace(o1)){
356  space1 = (dSpaceID)o1;
357  if (MY_VERBOSITY > 2){
358  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));
359  }
360  }
361  else{ //it's a geom
362  getGeomClassName(dGeomGetClass(o1),geom1className);
363  superSpace1 = dGeomGetSpace(o1);
364  geom1namesIt = odeinit._iCub->dGeomNames.find(o1);
365  if (geom1namesIt != odeinit._iCub->dGeomNames.end()){
366  geom1name = geom1namesIt->second;
367  if (MY_VERBOSITY > 2) 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));
368  }
369  else{
370  if (MY_VERBOSITY > 2) 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));
371  }
372  }
373 
374  if (dGeomIsSpace(o2)){
375  space2 = (dSpaceID)o2;
376  if (MY_VERBOSITY > 2){
377  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));
378  }
379  } else {
380  getGeomClassName(dGeomGetClass(o2),geom2ClassName);
381  superSpace2 = dGeomGetSpace(o2);
382  geom2namesIt = odeinit._iCub->dGeomNames.find(o2);
383  if (geom2namesIt != odeinit._iCub->dGeomNames.end()){
384  geom2name = geom2namesIt->second;
385  if (MY_VERBOSITY > 2) 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));
386  }
387  else{
388  if (MY_VERBOSITY > 2) 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));
389  }
390  }
391 
392  // if at least one of the geoms is a space, we need to go deeper -> recursive calls
393  if (dGeomIsSpace(o1) || dGeomIsSpace(o2)){
394  if (dGeomIsSpace(o1) && dGeomIsSpace(o2)){ //if both are spaces, we exclude special combinations from the checking
395  if (((space1 == odeinit._iCub->iCubHeadSpace) && (space2 == odeinit._iCub->iCubTorsoSpace)) || ((space1 == odeinit._iCub->iCubTorsoSpace) && (space2 == odeinit._iCub->iCubHeadSpace))){
396  if (MY_VERBOSITY > 2) printf("%s Ignoring head vs. torso collision space checking.\n",indentString.c_str());
397  //these are unnecessary geoms to check, moreover 2 of these were colliding while not connected by a joint
398  }
399  else if (((space1 == odeinit._iCub->iCubLegsSpace) && (space2 == odeinit._iCub->iCubTorsoSpace)) || ((space1 == odeinit._iCub->iCubTorsoSpace) && (space2 == odeinit._iCub->iCubLegsSpace))){
400  if (MY_VERBOSITY > 2) printf("%s Ignoring legs vs. torso collision space checking.\n",indentString.c_str());
401  //these are unnecessary geoms to check - it always check collisions of geoms connected by a joint
402  }
403  else{
404  dSpaceCollide2(o1,o2,data,&nearCallback);
405  }
406  }
407  else{
408  dSpaceCollide2(o1,o2,data,&nearCallback);
409  }
410  //}
411  //if (dGeomIsSpace(o2)){
412  // dSpaceCollide2(o2,o1,data,&nearCallback); //start the recursion from the other end
413  //}
414  return;
415  }
416  /* Note we do not want to test intersections within a space,
417  * only between spaces. Therefore, we do not call dSpaceCollide ((dSpaceID)o1, data, &nearCallback) and the same for o2 */
418 
419  /* 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 */
420 
421  dBodyID b1 = dGeomGetBody(o1);
422  dBodyID b2 = dGeomGetBody(o2);
423  if (b1 && b2 && dAreConnectedExcluding (b1,b2,dJointTypeContact)){
424  if (MY_VERBOSITY > 2) printf("%s Collision ignored: the bodies of o1 and o2 are connected by a joint.\n",indentString.c_str());
425  return;
426  }
427  // list of self-collisions to ignore
428  if (selfCollisionOnIgnoreList(geom1name,geom2name)){
429  if (MY_VERBOSITY > 2){
430  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());
431  printf("%s Collision ignored (ignore list).\n",indentString.c_str());
432  }
433  return;
434  }
435 
436  if (MY_VERBOSITY > 2) printf("%s Collision candidate. Preparing contact joints.\n",indentString.c_str());
437  dContact contact[MAX_CONTACTS]; // up to MAX_CONTACTS contacts per box-box
438  int i;
439  for (i=0; i<MAX_CONTACTS; i++) {
440  contact[i].surface.mode = dContactSlip1| dContactSlip2| dContactBounce | dContactSoftCFM;
441  contact[i].surface.mu = dInfinity;
442  contact[i].surface.mu2 = 0;
443  contact[i].surface.bounce = 0.01;
444  contact[i].surface.bounce_vel = 0.01;
445  contact[i].surface.slip1 = (dReal)0.000001;
446  contact[i].surface.slip2 = (dReal)0.000001;
447  contact[i].surface.soft_cfm = 0.0001;
448  }
449  int numc = dCollide (o1,o2,MAX_CONTACTS,&contact[0].geom,sizeof(dContact));
450  if (numc > 0){
451  if (MY_VERBOSITY > 2) printf("%s Collision suspect confirmed. There are %d contacts - creating joints.\n",indentString.c_str(),numc);
452  dMatrix3 RI;
453  dRSetIdentity (RI);
454  if(contact[0].geom.pos[1]>CONTACT_HEIGHT_TRESHOLD_METERS){ //non-foot contact
455  if (MY_VERBOSITY > 1){
456  printf("%s ****** non-ground COLLISION, %d contacts - creating joints************************************************************\n",indentString.c_str(),numc);
457  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());
458  }
459  }
460  for (i=0; i<numc; i++) {
461  if (MY_VERBOSITY > 2) 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);
462  dJointID c = dJointCreateContact (odeinit.world,odeinit.contactgroup,contact+i);
463  dJointAttach (c,b1,b2);
464  // if (show_contacts) dsDrawBox (contact[i].geom.pos,RI,ss);
465  // check if the bodies are touch sensitive.
466  if (odeinit._iCub->actSkinEmul == "off"){ //this is the old implementation - hands (fingers and palm) are checked for touch
467  bool b1isTouchSensitive = isBodyTouchSensitive (b1);
468  bool b2isTouchSensitive = isBodyTouchSensitive (b2);
469  // if any of the bodies are touch sensitive...
470  if (b1isTouchSensitive || b2isTouchSensitive) {
471  // ... add a feedback structure to the contact joint.
472  if (MY_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);
473  dJointSetFeedback (c, &(touchSensorFeedbacks[nFeedbackStructs]));
475  }
476  }
477  else { //whole_body_skin_emul ~ actSkinEmul is on
478  /* here we treat all bodies belonging to the icub as touch sensitive
479  * we want to know if the geom is part of the iCub - that is its superSpace is one of the iCub subspaces*/
480 
481  if ((superSpace1 == odeinit._iCub->iCubHeadSpace) || (superSpace1 == odeinit._iCub->iCubLegsSpace)){
482  geom1isiCubPart = true;
483  }
484  else if ((superSpace1==odeinit._iCub->iCubTorsoSpace) || (superSpace1==odeinit._iCub->iCubLeftArmSpace) || (superSpace1== odeinit._iCub->iCubRightArmSpace)){
485  geom1isiCubPart = true;
486  geom1isTorsoOrArm = true;
487  }
488  // || (superSpace1 == iCub){ - this should never happen here - in the self-collision mode, the iCub space contains only subspaces - no geoms directly
489 
490  if ((superSpace2 == odeinit._iCub->iCubHeadSpace) || (superSpace2 == odeinit._iCub->iCubLegsSpace)){
491  geom2isiCubPart = true;
492  }
493  else if ((superSpace2==odeinit._iCub->iCubTorsoSpace) || (superSpace2==odeinit._iCub->iCubLeftArmSpace) || (superSpace2== odeinit._iCub->iCubRightArmSpace)){
494  geom2isiCubPart = true;
495  geom2isTorsoOrArm = true;
496  }
497 
498  // 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
499  if ( geom1isTorsoOrArm || geom2isTorsoOrArm){
500  if (MY_VERBOSITY > 2) printf("%s Adding tactile feedback for whole-body skinContact to this contact (ODE joint feedback counter: %d).\n",indentString.c_str(),nFeedbackStructs);
502  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);
503  }
504  else{
505  dJointSetFeedback (c, &(touchSensorFeedbacks[nFeedbackStructs]));
506  nFeedbackStructs++;
507  }
508  OdeInit::contactOnSkin_t contactOnSkin, contactOnSkin2;
509  if (geom1isiCubPart){
510  contactOnSkin.body_geom_space_id = superSpace1;
511  contactOnSkin.body_geom_id = o1;
512  contactOnSkin.body_index = 1;
513  contactOnSkin.contact_geom = contact[i].geom;
514  contactOnSkin.contact_joint = c;
515  odeinit.listOfSkinContactInfos.push_back(contactOnSkin);
516  }
517  if (geom2isiCubPart){
518  contactOnSkin2.body_geom_space_id = superSpace2;
519  contactOnSkin2.body_geom_id = o2;
520  contactOnSkin2.body_index = 2;
521  contactOnSkin2.contact_geom = contact[i].geom;
522  contactOnSkin2.contact_joint = c;
523  odeinit.listOfSkinContactInfos.push_back(contactOnSkin2);
524  }
525  }
526  else {
527  if (MY_VERBOSITY > 2) printf("%s Ignoring skin contact - so far only arms and torso are implemented.\n",indentString.c_str());
528  }
529  } //whole_body_skin_emul ~ actSkinEmul is on
530  if (MY_VERBOSITY > 2) printf("\n");
531  } // for numc - contacts
532  } // if (numc > 0)
533  else{
534  if (MY_VERBOSITY > 2) printf("%s Collision suspect NOT confirmed. There were %d contacts.\n",indentString.c_str(),numc);
535  }
536 }
537 
538 
539 bool OdeSdlSimulation::selfCollisionOnIgnoreList(string geom1_string, string geom2_string)
540 {
541  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) ) ){
542  return true;
543  }
544  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) ) ){
545  return true;
546  }
547 
548  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) ) ){
549  return true;
550  }
551  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) ) ){
552  return true;
553  }
554 
555  return false;
556 }
557 
558 // returns true if the body with the bodyID is a touch-sensitive body, returns false otherwise.
559 bool OdeSdlSimulation::isBodyTouchSensitive (dBodyID bodyID) {
560  OdeInit& odeinit = OdeInit::get();
561 
562  // check the smaller hand parts if the left hand is active.
563  if (odeinit._iCub->actLHand == "on") {
564  if (bodyID == odeinit._iCub->body[10]) {
565  return true;
566  } else if (bodyID == odeinit._iCub->body[30]) {
567  return true;
568  } else if (bodyID == odeinit._iCub->body[24]) {
569  return true;
570  } else if (bodyID == odeinit._iCub->body[25]) {
571  return true;
572  } else if (bodyID == odeinit._iCub->lhandfingers3) {
573  return true;
574  }
575  } else { // check the whole left hand body if the hand is not active.
576  if (bodyID == odeinit._iCub->l_hand) {
577  return true;
578  }
579  }
580 
581  // check the smaller hand parts if the right hand is active.
582  if (odeinit._iCub->actRHand == "on") {
583  if (bodyID == odeinit._iCub->body[11]) {
584  return true;
585  } else if (bodyID == odeinit._iCub->body[49]) {
586  return true;
587  } else if (bodyID == odeinit._iCub->body[43]) {
588  return true;
589  } else if (bodyID == odeinit._iCub->body[44]) {
590  return true;
591  } else if (bodyID == odeinit._iCub->rhandfingers3) {
592  return true;
593  }
594  } else { // check the whole right hand body if the hand is not active.
595  if (bodyID == odeinit._iCub->r_hand) {
596  return true;
597  }
598  }
599 
600  return false;
601 }
602 
603 // this is a function to mimic the sensor data from the physical icub fingertip/palm sensors
604 //but the palm cover is not being checked here
605 void OdeSdlSimulation::inspectHandTouch_icubSensors(Bottle& reportLeft, Bottle& reportRight, bool boolean) {
606  OdeInit& odeinit = OdeInit::get();
607  reportLeft.clear();
608  reportRight.clear();
609  int indicesLeft[6] = {24, 25, 26, 27, 30, 10};
610  int indicesRight[6] = {43, 44, 45, 46, 49, 11};
611 
612  if (odeinit._iCub->actLHand == "on" && odeinit._iCub->actRHand == "on" ){
613  double resultLeft=0, resultRight = 0;
614  for (int x = 0; x < 6; x++){
615  if (boolean){
616  resultLeft = odeinit._iCub->checkTouchSensor( indicesLeft[x] );
617  resultRight = odeinit._iCub->checkTouchSensor( indicesRight[x] );
618  }
619  else{
620  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( indicesLeft[x] );
621  resultRight = odeinit._iCub->checkTouchSensor_continuousValued( indicesRight[x] );
622  }
623 
624  if (x < 5){ //five fingers
625  for (int i = 0; i < 12; i++){
626  reportLeft.addDouble(resultLeft * 255);
627  reportRight.addDouble(resultRight * 255);
628  }
629  }
630  if (x == 5){
631  for (int y = 0; y<3; y++){
632  for (int i = 0; i < 12; i++){
633  reportLeft.addDouble(0.0);
634  reportRight.addDouble(0.0);
635  }
636  }
637  //these are palm taxels
638  for (int y = 0; y<4; y++){
639  for (int i = 0; i < 12; i++){
640  reportLeft.addDouble(resultLeft * 255);
641  reportRight.addDouble(resultRight * 255);
642  }
643  }
644  for (int y = 0; y<4; y++){
645  for (int i = 0; i < 12; i++){
646  reportLeft.addDouble(0.0);
647  reportRight.addDouble(0.0);
648  }
649  }
650  }
651  }
652  }//end lhand on rhand on
653  else if (odeinit._iCub->actLHand == "on" && odeinit._iCub->actRHand == "off" ){
654  double resultLeft=0, resultRight = 0;
655  for (int x = 0; x < 6; x++){
656  if (boolean){
657  resultLeft = odeinit._iCub->checkTouchSensor( indicesLeft[x] );
658  resultRight = odeinit._iCub->checkTouchSensor( odeinit._iCub->r_hand );
659  }
660  else{
661  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( indicesLeft[x] );
662  resultRight = odeinit._iCub->checkTouchSensor_continuousValued(odeinit._iCub->r_hand);
663  }
664  if (x < 5){
665  for (int i = 0; i < 12; i++){
666  reportLeft.addDouble(resultLeft * 255);
667  reportRight.addDouble(resultRight * 255);
668  }
669  }
670  if (x == 5){
671  for (int y = 0; y<3; y++){
672  for (int i = 0; i < 12; i++){
673  reportLeft.addDouble(0.0);
674  reportRight.addDouble(0.0);
675  }
676  }
677  for (int y = 0; y<4; y++){
678  for (int i = 0; i < 12; i++){
679  reportLeft.addDouble(resultLeft * 255);
680  reportRight.addDouble(resultRight * 255);
681  }
682  }
683  for (int y = 0; y<4; y++){
684  for (int i = 0; i < 12; i++){
685  reportLeft.addDouble(0.0);
686  reportRight.addDouble(0.0);
687  }
688  }
689  }
690  }
691  }//end lhand on rhand off
692  else if (odeinit._iCub->actRHand == "on" && odeinit._iCub->actLHand == "off" ){
693  double resultLeft=0, resultRight = 0;
694  for (int x = 0; x < 6; x++){
695  if (boolean){
696  resultLeft = odeinit._iCub->checkTouchSensor( odeinit._iCub->l_hand );
697  resultRight = odeinit._iCub->checkTouchSensor( indicesRight[x] );
698  }
699  else{
700  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( odeinit._iCub->l_hand );
701  resultRight = odeinit._iCub->checkTouchSensor_continuousValued( indicesRight[x] );
702  }
703 
704  if (x < 5){
705  for (int i = 0; i < 12; i++){
706  reportLeft.addDouble(resultLeft * 255);
707  reportRight.addDouble(resultRight * 255);
708  }
709  }
710  if (x == 5){
711  for (int y = 0; y<3; y++){
712  for (int i = 0; i < 12; i++){
713  reportLeft.addDouble(0.0);
714  reportRight.addDouble(0.0);
715  }
716  }
717  for (int y = 0; y<4; y++){
718  for (int i = 0; i < 12; i++){
719  reportLeft.addDouble(resultLeft * 255);
720  reportRight.addDouble(resultRight * 255);
721  }
722  }
723  for (int y = 0; y<4; y++){
724  for (int i = 0; i < 12; i++){
725  reportLeft.addDouble(0.0);
726  reportRight.addDouble(0.0);
727  }
728  }
729  }
730  }
731  }//end lhand off rhand on
732  else{//both off
733  for (int x = 0; x < 6; x++){
734  double resultLeft=0, resultRight = 0;
735  if (boolean){
736  resultLeft = odeinit._iCub->checkTouchSensor( odeinit._iCub->l_hand );
737  resultRight = odeinit._iCub->checkTouchSensor( odeinit._iCub->r_hand );
738  }
739  else{
740  resultLeft = odeinit._iCub->checkTouchSensor_continuousValued( odeinit._iCub->l_hand );
741  resultRight = odeinit._iCub->checkTouchSensor_continuousValued(odeinit._iCub->r_hand);
742  }
743 
744  if (x < 5){
745  for (int i = 0; i < 12; i++){
746  reportLeft.addDouble(resultLeft * 255);
747  reportRight.addDouble(resultRight * 255);
748  }
749  }
750  if (x == 5){
751  for (int y = 0; y<3; y++){
752  for (int i = 0; i < 12; i++){
753  reportLeft.addDouble(0.0);
754  reportRight.addDouble(0.0);
755  }
756  }
757  for (int y = 0; y<4; y++){
758  for (int i = 0; i < 12; i++){
759  reportLeft.addDouble(resultLeft * 255);
760  reportRight.addDouble(resultRight * 255);
761  }
762  }
763  for (int y = 0; y<4; y++){
764  for (int i = 0; i < 12; i++){
765  reportLeft.addDouble(0.0);
766  reportRight.addDouble(0.0);
767  }
768  }
769  }
770  }
771  }//end both off
772 }
773 
774 
775 void OdeSdlSimulation::getAngles(const dReal *m, float& z, float& y, float& x) {
776  const dReal eps = 0.00001;
777 
778  y = -asin(m[2]);
779  float c = cos(y);
780 
781  if (fabs(c)>eps) {
782  x = atan2(-m[6]/c,m[10]/c);
783  z = atan2(-m[1]/c,m[0]/c);
784  } else {
785  x = 0;
786  z = -atan2(m[4],m[5]);
787  }
788  x *= -180/M_PI;
789  y *= 180/M_PI;
790  z *= 180/M_PI;
791 }
792 
793 void OdeSdlSimulation::initViewpoint() {
794  xpos = 0;
795  ypos = 1;
796  zpos = 1;
797  xrot = 25;
798  yrot = 0;
799  zrot = 0;
800 }
801 
802 void OdeSdlSimulation::mouseMovement(float x, float y) {
803  float diffx = x-lastx; //check the difference between the current x and the last x position
804  float diffy = y-lasty; //check the difference between the current y and the last y position
805  lastx =x; //set lastx to the current x position
806  lasty =y; //set lasty to the current y position
807  xrot += (float) diffy; //set the xrot to xrot with the addition of the difference in the y position
808  yrot += (float) diffx; //set the xrot to yrot with the addition of the difference in the x position
809 }
810 
811 void OdeSdlSimulation::draw_screen() {
812  OdeInit& odeinit = OdeInit::get();
813 
814  glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT); // refresh opengl
815 
816  if (extractImages || odeinit._iCub->actVision == "on"){
818  }
819 
820  glViewport(0,0,width,height);
821  glMatrixMode (GL_PROJECTION);
822  glLoadIdentity();
823  gluPerspective( 75, (float)width/height, 0.01, 100.0 );
824  glMatrixMode (GL_MODELVIEW);
825  glLoadIdentity();
826  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
827  glRotatef (xrot, 1,0,0);
828  glRotatef (yrot, 0,1,0);
829  glRotatef (zrot, 0,0,1);
830  glTranslated(-xpos,-ypos,-zpos);
831 
832  // set up any video textures
833 
834  if (video!=0)
835  DrawVideo(video);
836 
837  //draw the ground
838  glColor3d(0.5,0.5,1);
839  glPushMatrix();
840  glRotatef(90.0,1,0,0);
841  glRotatef(180.0,0,1,0);
842  DrawGround(false);
843  glPopMatrix();
844  glDisable(GL_TEXTURE_2D);
845  draw();
846  glEnable(GL_TEXTURE_2D);
847  drawSkyDome(0,0,0,50,50,50); // Draw the Skybox
848  SDL_GL_SwapBuffers();// Swap Buffers
849 }
850 
851 
852 
853 void OdeSdlSimulation::retreiveInertialData(Bottle& inertialReport) {
854  OdeInit& odeinit = OdeInit::get();
855  static dReal OldLinearVel[3], LinearVel[3], LinearAccel[3];
856  inertialReport.clear();
857 
858  //get euler angles from quaternions
859  dQuaternion angles;
860  dGeomGetQuaternion( odeinit._iCub->inertialGeom, angles );
861  dReal w, x, y, z;
862  w = angles[0];
863  x = angles[1];
864  y = angles[2];
865  z = angles[3];
866 
867  double sqw = w * w;
868  double sqx = x * x;
869  double sqy = y * y;
870  double sqz = z * z;
871  float roll, pitch, yaw;
872 
873  double unit = sqx + sqy + sqz + sqw; // if normalised is one, otherwise is correction factor
874  double test = x*y + z*w;
875  if (test > 0.499*unit) { // singularity at north pole
876  roll = 2 * atan2(x,w);
877  pitch = M_PI/2;
878  yaw = 0;
879  return;
880  }
881  if (test < -0.499*unit) { // singularity at south pole
882  roll = -2 * atan2(x,w);
883  pitch = -M_PI/2;
884  yaw = 0;
885  return;
886  }
887  roll =(float) ( atan2(2.0*y*w-2*x*z , sqx - sqy - sqz + sqw) ); //z
888  pitch = (float) (atan2(2.0*x*w-2*y*z , -sqx + sqy - sqz + sqw) );//x
889  yaw = asin(2*test/unit);//y
890 
891  //roll = dBodyGetRotation(odeinit._iCub->head)[4]; // was 1
892  //pitch = dBodyGetRotation(odeinit._iCub->head)[6];
893  //yaw = dBodyGetRotation(odeinit._iCub->head)[2];
894 
895  //Add Euler angles roll pitch yaw
896  inertialReport.addDouble( -yaw * 180/M_PI);// yaw
897  inertialReport.addDouble( -pitch * 180/M_PI);// pitch
898  inertialReport.addDouble( roll * 180/M_PI);// roll
899 
900  /*//in order to calculate linear acceleration (make sure of body) Inertial Measurement Unit IMU
901  LinearVel[0] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[0];
902  LinearVel[1] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[1];
903  LinearVel[2] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[2];
905  LinearAccel[0] = ( LinearVel[0] - OldLinearVel[0] ) / 0.02;
906  LinearAccel[1] = ( LinearVel[1] - OldLinearVel[1] ) / 0.02;
907  LinearAccel[2] = ( LinearVel[2] - OldLinearVel[2] ) / 0.02;
908  OldLinearVel[0] = LinearVel[0];
909  OldLinearVel[1] = LinearVel[1];
910  OldLinearVel[2] = LinearVel[2];*/
911 
913  Vector grav,grav1,grav2,grav3;
914  grav.resize(3);
915  grav1.resize(3);
916  grav2.resize(3);
917  grav3.resize(3);
918  double theta;
919 
920  grav[0]=0;
921  grav[1]=0;
922  grav[2]=9.81;
923 
924  theta = pitch;
925  grav1[0]=grav[0]*cos(theta)+grav[2]*sin(theta);
926  grav1[1]=grav[1];
927  grav1[2]=grav[0]*(-sin(theta))+grav[2]*cos(theta);
928 
929  theta = yaw;
930  grav2[0]=grav1[0];
931  grav2[1]=grav1[1]*cos(theta)+grav1[2]*(-sin(theta));
932  grav2[2]=grav1[1]*sin(theta)+grav1[2]*cos(theta);
933 
934  theta = roll;
935  grav3[0]=grav2[0]*cos(theta)+grav2[1]*(-sin(theta));
936  grav3[1]=grav2[0]*sin(theta)+grav2[1]*cos(theta);
937  grav3[2]=grav2[2];
938 
939  inertialReport.addDouble( grav3[0] );
940  inertialReport.addDouble( grav3[1] );
941  inertialReport.addDouble( grav3[2] );
942 
943  //Add angular velocity
944  inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[2]*CTRL_RAD2DEG);
945  inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[0]*CTRL_RAD2DEG);
946  inertialReport.addDouble( dBodyGetAngularVel(odeinit._iCub->inertialBody)[1]*CTRL_RAD2DEG);
947 
948  //Add magnetic fields
949  inertialReport.addDouble(0.0);
950  inertialReport.addDouble(0.0);
951  inertialReport.addDouble(0.0);
952 }
953 
954 int OdeSdlSimulation::thread_ode(void *unused) {
955  //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
956  double cpms = 1e3 / CLOCKS_PER_SEC;
957  long lastOdeProcess = (long) (clock()*cpms);
958  double avg_ode_step_length = 0.0;
959  long count = 0;
960  simrun = true;
961  double timeCache = ode_step_length;
962  long lastTimeCacheUpdate = (long) (clock()*cpms);
963  double alpha = 0.99;
964  // if realTime=true when delays occur the simulation tries to recover by running more steps in a row
965  // if realTime=false the simulation executes the simulation steps with a fixed rate irregardless of delays
966  bool realTime = true;
967  long temp;
968 
969  while (simrun) {
970  temp = (long) (clock()*cpms);
971  timeCache += temp - lastTimeCacheUpdate;
972  lastTimeCacheUpdate = temp;
973  while(timeCache < ode_step_length){
974  SDL_Delay((unsigned int)(ode_step_length-timeCache));
975  temp = (long) (clock()*cpms);
976  timeCache += temp - lastTimeCacheUpdate;
977  lastTimeCacheUpdate = temp;
978  }
979 
980  /*if(timeCache >= 2.0*ode_step_length)
981  printf("Simulation delay: running %d steps in a row to recover.\n", (int)(timeCache/ode_step_length));*/
982 
983  while(timeCache >= ode_step_length){
984  count++;
985  lastOdeProcess = (long) (clock()*cpms);
986  ODE_process(1, (void*)1);
987  avg_ode_step_length = alpha*avg_ode_step_length + (1.0-alpha)*((long) (clock()*cpms) -lastOdeProcess);
988 
989  if(realTime)
990  timeCache -= ode_step_length;
991  else
992  timeCache = 0.0;
993 
994  // check if the desired timestep is achieved, if not, print a warning msg
995  if(count % (10000/ode_step_length)==0){
996  if(avg_ode_step_length >= ode_step_length+1)
997  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",
998  ode_step_length, avg_ode_step_length);
999  else if(avg_ode_step_length <= ode_step_length-1)
1000  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",
1001  ode_step_length, avg_ode_step_length);
1002  }
1003  }
1004  }
1005  return(0);
1006 }
1007 
1008 Uint32 OdeSdlSimulation::ODE_process(Uint32 interval, void *param) {
1009  OdeInit& odeinit = OdeInit::get();
1010  //static clock_t startTimeODE= clock(), finishTimeODE= clock();
1011  //startTimeODE = clock();
1012 
1013  odeinit.mutex.wait();
1014  nFeedbackStructs=0;
1015 
1016  if (MY_VERBOSITY > 2) printf("\n ***info code collision detection ***\n");
1017  if (MY_VERBOSITY > 2) printf("OdeSdlSimulation::ODE_process: dSpaceCollide(odeinit.space,0,&nearCallback): will test iCub space against the rest of the world (e.g. ground).\n");
1018  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
1019  if (odeinit._iCub->actSelfCol == "on"){
1021  if (MY_VERBOSITY > 2){
1022  printf("OdeSdlSimulation::ODE_process: dSpaceCollide(odeinit._iCub->iCub,0,&nearCallback): will test iCub subspaces against each other.\n");
1023  }
1024  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
1025  }
1026  }
1027  if (MY_VERBOSITY > 2) printf("***END OF info code collision detection ***\n");
1028 
1029  dWorldStep(odeinit.world, dstep);
1030  // do 1 TIMESTEP in controllers (ok to run at same rate as ODE: 1 iteration takes about 300 times less computation time than dWorldStep)
1031  for (int ipart = 0; ipart<MAX_PART; ipart++) {
1032  if (odeinit._controls[ipart] != NULL) {
1033  odeinit._controls[ipart]->jointStep();
1034  }
1035  }
1036  odeinit.sync = true;
1037  odeinit.mutex.post();
1038 
1039  if (odeinit._iCub->actSkinEmul == "off"){
1041  Bottle reportLeft;
1042  Bottle reportRight;
1043  bool boolean = true;
1044  if (odeinit._iCub->actPressure == "on"){
1045  boolean = false;
1046  }
1047  inspectHandTouch_icubSensors(reportLeft, reportRight, boolean);//inspectBodyTouch_continuousValued(report);
1048 
1050  robot_streamer->sendTouchLeftHand( reportLeft );
1051 
1053  robot_streamer->sendTouchRightHand( reportRight );
1054  }
1055  }
1056  else{ // actSkinEmul == "on"
1061  //these are emulating the skin in the covers on the iCub body. For the moment, whole skin part will be activated if it was touched
1062  inspectWholeBodyContactsAndSendTouch();
1063  }
1064  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
1065  // the contacts can be visualized using the icubGui (not skinGui)
1066  skinContactList mySkinContactList;
1067  if (! odeinit.listOfSkinContactInfos.empty()){
1068  if ((odeinit._iCub->actHead=="off") || (odeinit._iCub->actTorso=="off") || (odeinit._iCub->actLArm=="off") || (odeinit._iCub->actRArm=="off")){
1069  mySkinContactList.clear();
1070  printf("Warning: With self-collisions on but head/torso/left_arm/right_arm off, the skinContactList can't be created.\n");
1071  }
1072  else{
1073  processWholeBodyCollisions(mySkinContactList);
1074  }
1075  }
1076  robot_streamer->sendSkinEvents(mySkinContactList); //we send even if empty
1077  }
1078  odeinit.listOfSkinContactInfos.clear();
1079  }
1080 
1081  dJointGroupEmpty (odeinit.contactgroup);
1082 
1084  Bottle inertialReport;
1085  retreiveInertialData(inertialReport);
1086  robot_streamer->sendInertial(inertialReport);
1087  }
1088 
1089  //go and check if torques are needed
1091 
1092  odeinit._iCub->setJointControlAction();
1093 
1094  //finishTimeODE = clock() ;
1095  //SPS();
1096  //printf("ODE=%lf\n",(double)(finishTimeODE - startTimeODE) / CLOCKS_PER_SEC);
1097  return(interval);
1098 }
1099 
1100 
1101 /*int OdeSdlSimulation::thread_func(void *unused) {
1102  // this needs to be kept synchronized with the timestep in
1103  // dWorldStep, in order to get correct world clock time
1104  // --paulfitz
1105  int delay = 50;
1106  id = SDL_AddTimer( delay, &OdeSdlSimulation::ODE_process, (void*)1);
1107 
1108  return(0);
1109 }
1110 */
1111 /*
1112  static void SPS()
1113  {
1114  static float sps = 0.0f;
1115  static float previousTime = 0.0f;
1116  static int currentsps;
1117  static char strSPS[60] = {0};
1118 
1119  float currentTime = (GetTickCount() * 0.001f);
1120 
1121  ++sps; // Increment the SPS counter
1122 
1123  if( currentTime - previousTime > 1.0f ){
1124  previousTime = currentTime;
1125  currentsps = int(sps);
1126  printf("current SPS: %d\n",currentsps);
1127  sps = 0.0f;
1128  }
1129  }
1130 */
1131 
1132 void OdeSdlSimulation::sighandler(int sig) {
1133  OdeInit& odeinit = OdeInit::get();
1134  odeinit.stop = true;
1135  cout << "\nCAUGHT Ctrl-c" << endl;
1136 }
1137 
1138 void OdeSdlSimulation::simLoop(int h,int w) {
1139  fprintf(stdout, "***** OdeSdlSimulation::simLoop \n");
1140  OdeInit& odeinit = OdeInit::get();
1141 
1142  SDL_Init(SDL_INIT_TIMER | SDL_GL_ACCELERATED_VISUAL);
1143  SDL_SetVideoMode(h,w,32,SDL_OPENGL | SDL_RESIZABLE);// | SDL_SWSURFACE| SDL_ANYFORMAT); // on init
1144 
1145  dAllocateODEDataForThread(dAllocateMaskAll);
1146  ConstString logo = robot_config->getFinder().findFile("logo");
1147 
1148  image = SDL_LoadBMP(robot_config->getFinder().findFile(logo.c_str()).c_str());
1149  SDL_WM_SetIcon(image,0);
1150  SDL_FreeSurface(image);
1151  SDL_WM_SetCaption("iCub Simulator", "image");
1152 
1153  //SDL_Thread *thread;
1154  SDL_Thread *ode_thread = SDL_CreateThread(thread_ode, NULL);
1155  //thread = SDL_CreateThread(thread_func, NULL);
1156 
1157  if ( ode_thread == NULL ) {
1158  fprintf(stderr, "Unable to create thread: %s\n", SDL_GetError());
1159  return;
1160  }
1161 
1162  initViewpoint();
1163  bool ok = setup_opengl(robot_config->getFinder());
1164  if (!ok) return;
1165  startTime = (long) clock();
1166  odeinit.stop = false;
1167 
1168  yarp::os::signal(yarp::os::YARP_SIGINT, sighandler);
1169  yarp::os::signal(yarp::os::YARP_SIGTERM, sighandler);
1170 
1171  glrun = true;
1172  odeinit._wrld->WAITLOADING = false;
1173  odeinit._wrld->static_model = false;
1174  long prevTime = (long) clock();
1175  long timeLeft;
1176 
1177  if (odeinit._iCub->actStartHomePos == "on"){
1178  odeinit.sendHomePos();
1179  }
1180  if (odeinit._iCub->actSelfCol == "on") {
1181  if (odeinit._iCub->actStartHomePos == "on"){
1182  Time::delay(2.0); //we want to set this trigger on only after the robot is in home pos -
1183  //it's initial configuration is with arms inside the thighs - generating many self-collisions
1185  }
1186  else{
1187  fprintf(stdout, "Warning: the robot is not starting from HomePos and self-collision mode is on. The initial posture is already self-colliding.\n");
1189  }
1190  }
1191 
1192  while(!odeinit.stop) {
1193  /* Process incoming events. */
1194  process_events();
1195  /* Draw the screen. */
1196  if ( !odeinit._wrld->WAITLOADING ){
1197  if (glrun) {
1198  odeinit.mutexTexture.wait();
1199  draw_screen();
1200  odeinit.mutexTexture.post();
1201  // check for framerate
1202  timeLeft = (prevTime - (long) clock()) + gl_frame_length;
1203  //cout << "check for framerate " << timeLeft << endl;
1204  if (timeLeft > 0)
1205  { // if there is still time left in this frame, just wait
1206  SDL_Delay(timeLeft);
1207  }
1208  prevTime = (long) clock();
1209  } else {
1210  SDL_Delay(100);
1211  }
1212  }
1213  else{
1214  glFinish();
1215  glFlush();
1216  //make sure it can also be done for static objects
1217  if (odeinit._wrld->static_model){
1218  odeinit._wrld->loadTexture(odeinit._wrld->texture, odeinit._wrld->s_modelTexture[odeinit._wrld->s_MODEL_NUM-1]);
1219  }else{
1220  odeinit._wrld->loadTexture(odeinit._wrld->texture, odeinit._wrld->modelTexture[odeinit._wrld->MODEL_NUM-1]);
1221  }
1222  odeinit._wrld->WAITLOADING = false;
1223  odeinit._wrld->static_model = false;
1224  }
1225  }
1226  printf("\n\nStopping SDL and ODE threads...\n");
1227  //stop the timer
1228  //SDL_RemoveTimer(id);
1229  //Stop the thread
1230  //SDL_KillThread( thread );
1231  simrun = false;
1232  //SDL_WaitThread( thread, NULL );
1233  SDL_WaitThread( ode_thread, NULL );
1234  //SDL_Quit();
1235 }
1236 
1237 void OdeSdlSimulation::drawView(bool left, bool right, bool wide) {
1238  OdeInit& odeinit = OdeInit::get();
1239  const dReal *pos;
1240  const dReal *rot;
1241  glViewport(0,0,cameraSizeWidth,cameraSizeHeight);
1242  glMatrixMode (GL_PROJECTION);
1243 
1244  if (left){
1245  glLoadIdentity();
1246  gluPerspective( fov_left, (float) width_left/height_left, 0.04, 100.0 );
1247  pos = dGeomGetPosition(odeinit._iCub->Leye1_geom);
1248  rot = dGeomGetRotation(odeinit._iCub->Leye1_geom);
1249  glMatrixMode (GL_MODELVIEW);
1250  glLoadIdentity();
1251  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1252  gluLookAt(
1253  pos[0],
1254  pos[1],
1255  pos[2],
1256  pos[0] + rot[2],
1257  pos[1] + rot[6],
1258  pos[2] + rot[10],
1259  -rot[4], 1, 0
1260  );
1261  }
1262  if (right){
1263  glLoadIdentity();
1264  gluPerspective( fov_right, (float) width_right/height_right, 0.04, 100.0 );//55.8
1265  pos = dGeomGetPosition(odeinit._iCub->Reye1_geom);
1266  rot = dGeomGetRotation(odeinit._iCub->Reye1_geom);
1267  glMatrixMode (GL_MODELVIEW);
1268  glLoadIdentity();
1269  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1270  gluLookAt(
1271  pos[0],
1272  pos[1],
1273  pos[2],
1274  pos[0] + rot[2],
1275  pos[1] + rot[6],
1276  pos[2] + rot[10],
1277  -rot[4], 1, 0
1278  );
1279  }
1280  if (wide){
1281  glLoadIdentity();
1282  gluPerspective( 55.8, (float) cameraSizeWidth/cameraSizeHeight, 0.04, 100.0 );//here nothing to do with cameras
1283  glMatrixMode (GL_MODELVIEW);
1284  glLoadIdentity();
1285  glLightfv(GL_LIGHT0, GL_POSITION, light_position);
1286  glRotatef (xrot, 1,0,0);
1287  glRotatef (yrot, 0,1,0);
1288  glTranslated(-xpos,-ypos,-zpos);
1289  }
1290 
1291  //draw the ground
1292  glColor3d(0.5,0.5,1);
1293  glEnable(GL_TEXTURE_2D);
1294  glPushMatrix();
1295  glRotatef(90.0,1,0,0);
1296  glRotatef(180.0,0,1,0);
1297  DrawGround(false);
1298  glPopMatrix();
1299  glDisable(GL_TEXTURE_2D);
1300  draw();//robot
1301  glEnable(GL_TEXTURE_2D);
1302  drawSkyDome(0,0,0,50,50,50); // Draw the Skybox
1303 }
1304 
1306  glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT); // refresh opengl
1307 }
1308 
1310 }
1311 
1313  RobotConfig *config) {
1314  OdeInit& odeinit = OdeInit::get();
1315  if (video!=NULL) {
1316  fprintf(stderr, "Only one Simulation object allowed\n");
1317  yarp::os::exit(1);
1318  }
1319  robot_streamer = streamer;
1320  robot_config = config;
1321 
1322  ode_step_length = config->getWorldTimestep();
1323  dstep = ode_step_length*1e-3;
1324 
1325  video = new VideoTexture;
1326  string moduleName = odeinit.getName();
1327  video->setName( moduleName );
1328  odeinit._iCub->eyeLidsPortName = moduleName;
1329  Property options;
1330 
1331  //get the camera calibration parameters
1332  string camcalib_context=robot_config->getFinder().check("camcalib_context",
1333  Value("cameraCalibration")).asString().c_str();
1334  string camcalib_file=robot_config->getFinder().check("camcalib_file",
1335  Value("icubSimEyes.ini")).asString().c_str();
1336 
1337  ResourceFinder rf_camcalib;
1338  rf_camcalib.setVerbose();
1339  rf_camcalib.setDefaultContext(camcalib_context.c_str());
1340  rf_camcalib.setDefaultConfigFile(camcalib_file.c_str());
1341  rf_camcalib.configure(0,NULL);
1342 
1343  //left
1344  Bottle &bCalibLeft=rf_camcalib.findGroup("CAMERA_CALIBRATION_LEFT");
1345  width_left=bCalibLeft.check("w",Value(320)).asInt();
1346  height_left=bCalibLeft.check("h",Value(240)).asInt();
1347 
1350 
1351  double focal_length_left=bCalibLeft.check("fy",Value(257.34)).asDouble();
1352  fov_left=2*atan2((double)height_left,2*focal_length_left)*180.0/M_PI;
1353 
1354  //right
1355  Bottle &bCalibRight=rf_camcalib.findGroup("CAMERA_CALIBRATION_RIGHT");
1356  width_right=bCalibRight.check("w",Value(320)).asInt();
1357  height_right=bCalibRight.check("h",Value(240)).asInt();
1358 
1359  double focal_length_right=bCalibRight.check("fy",Value(257.34)).asDouble();
1360  fov_right=2*atan2((double)height_right,2*focal_length_right)*180.0/M_PI;
1361  //--------------------------------------//
1362 
1363 
1364  ConstString videoconf = robot_config->getFinder().findFile("video");
1365  options.fromConfigFile(videoconf.c_str());
1366 
1367  Bottle textures = *options.find("textures").asList();
1368  for (int i=0; i<textures.size(); i++) {
1369  ConstString name = textures.get(i).asString();
1370  printf("Adding video texture %s\n", name.c_str());
1371  video->add(options.findGroup(name.c_str()));
1372  }
1373 }
1374 
1376  delete video;
1377 }
1378 
1379 
1381  OdeInit& odeinit = OdeInit::get();
1382  if (reset) {
1383  odeinit.sync = false;
1384  }
1385  return odeinit.sync;
1386 }
1387 
1388 
1389 bool OdeSdlSimulation::getTrqData(Bottle data) {
1390  OdeInit& odeinit = OdeInit::get();
1391  for (int s=0; s<data.size(); s++){
1392  odeinit._iCub->torqueData[s] = data.get(s).asDouble();
1393  //fprintf(stdout,"torques... %lf \n",odeinit._iCub->torqueData[s]);
1394  }
1395  return true;
1396 }
1397 
1398 
1399 
1400 bool OdeSdlSimulation::getImage(ImageOf<PixelRgb>& target) {
1401  int w = cameraSizeWidth;
1402  int h = cameraSizeHeight;
1403  int p = 3;
1404 
1405  char *buf=new char[w * h * p];
1406  glReadPixels( 0, 0, w, h, GL_RGB, GL_UNSIGNED_BYTE, buf);
1407  ImageOf<PixelRgb> img;
1408  img.setQuantum(1);
1409  img.setExternal(buf,w,h);
1410 
1411  // inefficient flip!
1412  target.resize(img);
1413  int ww = img.width();
1414  int hh = img.height();
1415  for (int x=0; x<ww; x++) {
1416  for (int y=0; y<hh; y++) {
1417  target(x,y) = img(x,hh-1-y);
1418  }
1419  }
1420  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
1421  delete[] buf;
1422  return true;
1423 }
1424 
1425 
1426 
1427 void OdeSdlSimulation::processWholeBodyCollisions(skinContactList& skin_contact_list)
1428 {
1429  SkinPart skinPart; // id of the part of the skin (e.g. left_hand, right_forearm, left_upper_arm)
1430  BodyPart bodyPart; // id of the body part
1431  bool skinCoverFlag;
1432  Vector geoCenter_SIM_FoR_forHomo(4,0.0), normal_SIM_FoR_forHomo(4,0.0);
1433  Vector force_SIM_FoR_forHomo(4,0.0), moment_SIM_FoR_forHomo(4,0.0);
1434  Vector v1(4,0.0); //auxilliary vector
1435  Vector geoCenter_link_FoR(3,0.0), normal_link_FoR(3,0.0);
1436  Vector force_link_FoR(3,0.0), moment_link_FoR(3,0.0);
1437  double forceOnBody_magnitude;
1438  double left_arm_encoders[16], right_arm_encoders[16], torso_encoders[3], head_encoders[6];
1439  Vector left_arm_for_iKin(10,0.0), right_arm_for_iKin(10,0.0), inertial_for_iKin(6,0.0);
1440  Matrix T_root_to_link = yarp::math::zeros(4,4);
1441  Matrix T_link_to_root = yarp::math::zeros(4,4);
1442  std::vector<unsigned int> taxel_list;
1443 
1444  taxel_list.push_back(1); // we will always emulate one activated "taxel" per contact joint - say taxel "1"
1445  OdeInit& odeinit = OdeInit::get();
1446  odeinit._controls[PART_ARM_LEFT]->getEncodersRaw(left_arm_encoders);
1447  odeinit._controls[PART_ARM_RIGHT]->getEncodersRaw(right_arm_encoders);
1448  odeinit._controls[PART_TORSO]->getEncodersRaw(torso_encoders);
1449  odeinit._controls[PART_HEAD]->getEncodersRaw(head_encoders); //first three are probably neck joints, then the eyes
1450 
1451  for (int j=0;j<TORSO_DOF;j++){
1452  left_arm_for_iKin(j)=torso_encoders[j]; //first 3 joints - 0 to 2 - in iKin arm are torso joints
1453  right_arm_for_iKin(j)=torso_encoders[j];
1454  inertial_for_iKin(j)=torso_encoders[j];
1455  }
1456  for (int l=0;l<7;l++){
1457  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)
1458  right_arm_for_iKin(l+TORSO_DOF) = right_arm_encoders[l];
1459  }
1460  for (int m=0;m<3;m++){
1461  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)
1462  }
1463 
1464  odeinit._iCub->iKinLeftArm.setAng(left_arm_for_iKin);
1465  odeinit._iCub->iKinRightArm.setAng(right_arm_for_iKin);
1466  odeinit._iCub->iKinInertialSensor.setAng(inertial_for_iKin);
1467 
1468  if (MY_VERBOSITY > 0) printf("OdeSdlSimulation::processWholeBodyCollisions:There were %lu iCub collisions to process. \n", odeinit.listOfSkinContactInfos.size());
1469  for (list<OdeInit::contactOnSkin_t>::iterator it = odeinit.listOfSkinContactInfos.begin(); it!=odeinit.listOfSkinContactInfos.end(); it++){
1470  geoCenter_SIM_FoR_forHomo.zero(); geoCenter_SIM_FoR_forHomo(3)=1.0; //setting the extra row to 1 - for multiplication by homogenous rototransl. matrix
1471  normal_SIM_FoR_forHomo.zero(); normal_SIM_FoR_forHomo(3)=1.0;
1472  force_SIM_FoR_forHomo.zero(); force_SIM_FoR_forHomo(3)=1.0;
1473  moment_SIM_FoR_forHomo.zero(); moment_SIM_FoR_forHomo(3)=1.0;
1474  geoCenter_link_FoR.zero();normal_link_FoR.zero();
1475  moment_link_FoR.zero();force_link_FoR.zero();
1476  forceOnBody_magnitude=0.0;
1477  skinPart = SKIN_PART_UNKNOWN; bodyPart = BODY_PART_UNKNOWN; skinCoverFlag = false;
1478  T_root_to_link.zero(); T_link_to_root.zero();
1479 
1480  odeinit._iCub->getSkinAndBodyPartFromSpaceAndGeomID((*it).body_geom_space_id,(*it).body_geom_id,skinPart,bodyPart,skinCoverFlag);
1481  for (int i=0;i<3;i++){
1482  geoCenter_SIM_FoR_forHomo(i)= (*it).contact_geom.pos[i]; //in global (i.e. simulator) coordinates
1483  normal_SIM_FoR_forHomo(i) = (*it).contact_geom.normal[i];
1484  }
1485  dJointFeedback * fb = dJointGetFeedback ((*it).contact_joint);
1486  if (fb==NULL){
1487  printf("Warning:OdeSdlSimulation::processWholeBodyCollisions: This joint (at %d skin part) has no feedback structure defined - contact force not available: setting to -1.\n",skinPart);
1488  forceOnBody_magnitude = -1;
1489  }
1490  else{
1491  //printf("OdeSdlSimulation::processWholeBodyCollisions: joint feedback structure:\n.");
1492  //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
1493  //printf("f2 force vector: %f %f %f \n",fb->f2[0],fb->f2[1],fb->f2[2]);
1494  //f2 force vector has same magnitude but opposite direction than f1
1495  for(int k=0;k<3;k++){
1496  if((*it).body_index == 1){
1497  force_SIM_FoR_forHomo(k)=fb->f1[k];
1498  moment_SIM_FoR_forHomo(k)=fb->t1[k];
1499  }
1500  else if((*it).body_index == 2){
1501  force_SIM_FoR_forHomo(k)=fb->f2[k];
1502  moment_SIM_FoR_forHomo(k)=fb->t2[k];
1503  }
1504  else{
1505  printf("ERROR:OdeSdlSimulation::processWholeBodyCollisions: unexpected body_index for colliding body: %d.\n",(*it).body_index);
1506  }
1507  }
1508  forceOnBody_magnitude=sqrt(force_SIM_FoR_forHomo(0)*force_SIM_FoR_forHomo(0) + force_SIM_FoR_forHomo(1)*force_SIM_FoR_forHomo(1)
1509  + force_SIM_FoR_forHomo(2)*force_SIM_FoR_forHomo(2));
1510  }
1511 
1512  //Let's do all the transformations
1513  //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
1514  // vectors (f1, m1) are originating from the global origin, i.e. they need to be translated to contact_geom.pos;
1515  //see the post in ode-users group "dJointFeedback and dContactGeom reference frame", 6.12.2013local FoR of the contact point;
1516 
1517  switch(bodyPart){
1518  case LEFT_ARM:
1519  T_root_to_link = odeinit._iCub->iKinLeftArm.getH(SkinPart_2_LinkNum[skinPart].linkNum + TORSO_DOF);
1520  //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
1521  break;
1522  case RIGHT_ARM:
1523  T_root_to_link = odeinit._iCub->iKinRightArm.getH(SkinPart_2_LinkNum[skinPart].linkNum + TORSO_DOF);
1524  break;
1525  case TORSO:
1526  T_root_to_link = odeinit._iCub->iKinInertialSensor.getH(SkinPart_2_LinkNum[skinPart].linkNum);
1527  // 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
1528  //- check " SKIN torso 2" in iCub/main/app/iCubGui/skeleton.ini
1529  //- importantly, this needs to be the iKinInertialSensor, not the iKin Arm;
1530  break;
1531  default:
1532  if (MY_VERBOSITY > 0) printf("OdeSdlSimulation::processWholeBodyCollisions: FoR transforms to BODY PART %d not implemented yet\n",bodyPart);
1533  continue;
1534  }
1535  T_link_to_root = SE3inv(T_root_to_link);
1536 
1537  v1.zero();
1538  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
1539  geoCenter_link_FoR = v1.subVector(0,2); //strip the last one away
1540 
1541  v1.zero();
1542  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * normal_SIM_FoR_forHomo;
1543  normal_link_FoR = v1.subVector(0,2);
1544 
1545  v1.zero();
1546  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * force_SIM_FoR_forHomo;
1547  force_link_FoR = v1.subVector(0,2);
1548 
1549  v1.zero();
1550  v1 = T_link_to_root * (odeinit._iCub->H_r2w) * moment_SIM_FoR_forHomo;
1551  moment_link_FoR = v1.subVector(0,2);
1552 
1553  //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
1554  //appropariate CoP / geoCenter to make the arrow to the taxel
1555  //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
1556  //forces along the normal and frictional forces perpendicular to the normal
1557  //alternatively, I could just take the magnitude from the force and send the normal as the direction
1558 
1559  //printf("Contact coordinates in ODE / SIM FoR: %s\n",geoCenter_SIM_FoR_forHomo.subVector(0,2).toString().c_str());
1560  Vector temp_v4(4,0.0);
1561  temp_v4 = (odeinit._iCub->H_r2w) * geoCenter_SIM_FoR_forHomo;
1562  //printf("Contact coordinates in robot root FoR: %s\n",temp_v4.subVector(0,2).toString().c_str());
1563  //printf("Left arm for iKin:\n %s \n",left_arm_for_iKin.toString().c_str());
1564  //printf("Rototranslation matrix root to link:\n %s\n",T_root_to_link.toString().c_str());
1565  //printf("Contact coordinates in link FoR: %s\n",geoCenter_link_FoR.toString().c_str());
1566  /*for (int l=0;l<2;l++){
1567  geoCenter_link_FoR(l)=0.0;
1568  force_link_FoR(l)=1.0;
1569  normal_link_FoR(l)=1.0;
1570  moment_link_FoR(l)=1.0;
1571  } */
1572  //forceOnBody_magnitude=10.0;
1573 
1574  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);
1575  //we have only one source of information - the contact as detected by ODE - therefore, we take the coordinates and set them both to CoP
1576  //(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.
1577  if (MY_VERBOSITY > 0) printf("Creating skin contact as follows: %s.\n",c.toString().c_str());
1578  skin_contact_list.push_back(c);
1579  } // odeinit.listOfSkinContactInfos - iterator
1580 }
1581 
1582 void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch()
1583 {
1584 
1585  std::map<SkinPart,bool> skinPartsTouched;
1586  SkinPart skinPart; // id of the part of the skin - from skinDynLib/common.h
1587  BodyPart bodyPart; // id of the body part
1588  bool skinCoverFlag = false;
1589  bool left_hand_notCover_touched = false;
1590  bool right_hand_notCover_touched = false;
1591  OdeInit& odeinit = OdeInit::get();
1592 
1593  skinPartsTouched[SKIN_LEFT_FOREARM]=false; skinPartsTouched[SKIN_LEFT_UPPER_ARM]=false;
1594  skinPartsTouched[SKIN_RIGHT_FOREARM]=false; skinPartsTouched[SKIN_RIGHT_FOREARM]=false;
1595  skinPartsTouched[SKIN_FRONT_TORSO]=false;
1596 
1597  for (list<OdeInit::contactOnSkin_t>::iterator it = odeinit.listOfSkinContactInfos.begin(); it!=odeinit.listOfSkinContactInfos.end(); it++){
1598  skinPart = SKIN_PART_UNKNOWN; bodyPart = BODY_PART_UNKNOWN; skinCoverFlag = false;
1599  odeinit._iCub->getSkinAndBodyPartFromSpaceAndGeomID((*it).body_geom_space_id,(*it).body_geom_id,skinPart,bodyPart,skinCoverFlag);
1600  //We emulate the skin of the iCub - covers + fingertips; the rest of the geoms will only be processed by the skinEvents
1601  if(skinCoverFlag){
1602  //if it was a cover that was touched, we will emulate the skin there - this includes the palm cover
1603  skinPartsTouched[skinPart]=true; //if the skinPart comes back as UNKNOWN, this is fine, we set it to true
1604  }
1605  else if(skinPart == SKIN_LEFT_HAND) {
1606  left_hand_notCover_touched = true; //these need special treatment because for the fingertip, we check the geoms, there are no covers there
1607  }
1608  else if(skinPart == SKIN_RIGHT_HAND) {
1609  right_hand_notCover_touched = true; //these need special treatment because for the fingertip, we check the geoms, there are no covers there
1610  }
1611  }
1612 
1613  //rewritten based on original inspectTouch_icubSensors, the output of actual pressure values is discontinued; the collisions with palm cover are added
1614  // the palm cover replaces sensing in the palm body
1616  Bottle bottleLeftHand;
1617  if (left_hand_notCover_touched || skinPartsTouched[SKIN_LEFT_HAND]){
1618  if (left_hand_notCover_touched){ // some part other than the palm cover was touched, need to check fingertips
1619  int bodyIndicesLeft[5] = {24, 25, 26, 27, 30};
1620  double resultLeft=0;
1621  for (int x = 0; x < 5; x++){
1622  if (odeinit._iCub->actLHand == "on"){
1623  resultLeft = odeinit._iCub->checkTouchSensor(bodyIndicesLeft[x]);
1624  }
1625  else{
1626  resultLeft = odeinit._iCub->checkTouchSensor(odeinit._iCub->l_hand);
1627  }
1628  //now filling up the bottle - the port output where 1-60 are taxels of fingertips (12 each);
1629  for (int i = 0; i < 12; i++){
1630  bottleLeftHand.addDouble(resultLeft * 255);
1631  }
1632  }
1633  }
1634  else{ //we fill the fingertip positions with 0s
1635  for (int i = 0; i < 60; i++){
1636  bottleLeftHand.addDouble(0.0);
1637  }
1638  }
1639  //now filling up the bottle - the port output: 61-96 zeros;
1640  for (int y = 0; y<36; y++){ //positions 61-96
1641  bottleLeftHand.addDouble(0.0);
1642  }
1643  if(skinPartsTouched[SKIN_LEFT_HAND]){ //palm cover
1644  //97-144 palm taxels (inside these, 107, 119, 131, and 139 are thermal pads ~ 0s);
1645  for (int y = 0; y<48; y++){
1646  bottleLeftHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now
1647  }
1648  }
1649  else{
1650  for (int y = 0; y<48; y++){
1651  bottleLeftHand.addDouble(0.0); //we ignore the thermal pad positions which should be 0s for now
1652  }
1653  }
1654  //filling the rest: 145-192 zeros.
1655  for (int y = 0; y<48; y++){
1656  bottleLeftHand.addDouble(0.0);
1657  }
1658  }
1659  else{
1660  bottleLeftHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1661  }
1662  robot_streamer->sendTouchLeftHand(bottleLeftHand);
1663  }
1664 
1665  //rewritten based on original inspectTouch_icubSensors, the output of actual pressure values is discontinued; the collisions with palm cover are added
1666  // the palm cover replaces sensing in the palm body
1668  Bottle bottleRightHand;
1669  if (right_hand_notCover_touched || skinPartsTouched[SKIN_RIGHT_HAND]){
1670  if (right_hand_notCover_touched){ // some part other than the palm cover was touched, need to check fingertips
1671  int bodyIndicesRight[5] = {43, 44, 45, 46, 49};
1672  double resultRight=0;
1673  for (int x = 0; x < 5; x++){
1674  if (odeinit._iCub->actRHand == "on"){
1675  resultRight = odeinit._iCub->checkTouchSensor(bodyIndicesRight[x]);
1676  }
1677  else{
1678  resultRight = odeinit._iCub->checkTouchSensor(odeinit._iCub->r_hand);
1679  }
1680  //now filling up the bottle - the port output where 1-60 are taxels of fingertips (12 each);
1681  for (int i = 0; i < 12; i++){
1682  bottleRightHand.addDouble(resultRight * 255);
1683  }
1684  }
1685  }
1686  else{ //we fill the fingertip positions with 0s
1687  for (int i = 0; i < 60; i++){
1688  bottleRightHand.addDouble(0.0);
1689  }
1690  }
1691  //now filling up the bottle - the port output: 61-96 zeros;
1692  for (int y = 0; y<36; y++){ //positions 61-96
1693  bottleRightHand.addDouble(0.0);
1694  }
1695  if(skinPartsTouched[SKIN_RIGHT_HAND]){ //palm cover
1696  //97-144 palm taxels (inside these, 107, 119, 131, and 139 are thermal pads ~ 0s);
1697  for (int y = 0; y<48; y++){
1698  bottleRightHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now
1699  }
1700  }
1701  else{
1702  for (int y = 0; y<48; y++){
1703  bottleRightHand.addDouble(0.0); //we ignore the thermal pad positions which should be 0s for now
1704  }
1705  }
1706  //filling the rest: 145-192 zeros.
1707  for (int y = 0; y<48; y++){
1708  bottleRightHand.addDouble(0.0);
1709  }
1710  }
1711  else{
1712  bottleRightHand = Bottle(odeinit._iCub->emptySkinActivationHand);
1713  }
1714  // printf("bottleRightHand: %s \n",bottleRightHand.toString().c_str());
1715  robot_streamer->sendTouchRightHand(bottleRightHand);
1716  }
1717 
1719  Bottle bottleLeftArm;
1720  if (skinPartsTouched[SKIN_LEFT_UPPER_ARM]){
1721  bottleLeftArm = Bottle(odeinit._iCub->fullSkinActivationUpperArm);
1722  }
1723  else{
1724  bottleLeftArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
1725  }
1726  robot_streamer->sendTouchLeftArm(bottleLeftArm);
1727  }
1729  Bottle bottleLeftForearm;
1730  if(skinPartsTouched[SKIN_LEFT_FOREARM]){
1731  bottleLeftForearm = Bottle(odeinit._iCub->fullSkinActivationForearm);
1732  // printf("bottleLeftForearm: %s \n",bottleLeftForearm.toString().c_str());
1733  }
1734  else{
1735  bottleLeftForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
1736  }
1737  robot_streamer->sendTouchLeftForearm(bottleLeftForearm);
1738  }
1740  Bottle bottleRightArm;
1741  if (skinPartsTouched[SKIN_RIGHT_UPPER_ARM]){
1742  bottleRightArm = Bottle(odeinit._iCub->fullSkinActivationUpperArm);
1743  }
1744  else{
1745  bottleRightArm = Bottle(odeinit._iCub->emptySkinActivationUpperArm);
1746  }
1747  robot_streamer->sendTouchRightArm(bottleRightArm);
1748  }
1750  Bottle bottleRightForearm;
1751  if(skinPartsTouched[SKIN_RIGHT_FOREARM]){
1752  bottleRightForearm = Bottle(odeinit._iCub->fullSkinActivationForearm);
1753  }
1754  else{
1755  bottleRightForearm = Bottle(odeinit._iCub->emptySkinActivationForearm);
1756  }
1757  robot_streamer->sendTouchRightForearm(bottleRightForearm);
1758  }
1760  Bottle bottleTorso;
1761  if(skinPartsTouched[SKIN_FRONT_TORSO]){
1762  bottleTorso = Bottle(odeinit._iCub->fullSkinActivationTorso);
1763  }
1764  else{
1765  bottleTorso = Bottle(odeinit._iCub->emptySkinActivationTorso);
1766  }
1767  robot_streamer->sendTouchTorso(bottleTorso);
1768  }
1769 }
1770 
1771 
1772 //Auxiliary function to print class of geom - according to section 9.5 of ODE manual
1773 std::string OdeSdlSimulation::getGeomClassName(const int geom_class,std::string & s)
1774 {
1775  switch(geom_class){
1776  case 0:
1777  s = "sphere";
1778  break;
1779  case 1:
1780  s = "box";
1781  break;
1782  case 2:
1783  s = "capsule";
1784  break;
1785  case 3:
1786  s = "cylinder";
1787  break;
1788  case 4:
1789  s = "plane";
1790  break;
1791  case 8:
1792  s= "triangle mesh";
1793  break;
1794  case 10:
1795  case 11:
1796  s = "simple space";
1797  break;
1798  case 12:
1799  s="hash space";
1800  break;
1801  default:
1802  s ="unknown type";
1803  break;
1804  }
1805  return s;
1806 
1807 }
static float hpr[8]
Definition: iCub_Sim.cpp:45
static float lasty
Definition: iCub_Sim.cpp:73
const Skin_2_Link SkinPart_2_LinkNum[SKIN_PART_SIZE]
Definition: common.h:117
static int mouseDiffy
Definition: iCub_Sim.cpp:49
static bool eyeCams
Definition: iCub_Sim.cpp:85
static SDL_Surface * image
Definition: iCub_Sim.cpp:80
#define MAX_PART
iCub::iKin::iCubInertialSensor iKinInertialSensor
Definition: iCub.h:272
virtual bool getTrqData(Bottle data)
Definition: iCub_Sim.cpp:1389
struct timeval prevTime[BOARD_NUM]
virtual bool shouldSendInertial()=0
static RobotConfig * robot_config
Definition: iCub_Sim.cpp:84
double checkTouchSensor_continuousValued(int bodyToCheck)
Definition: iCub.cpp:106
yarp::os::Semaphore mutex
Definition: OdeInit.h:64
yarp::os::Semaphore mutexTexture
Definition: OdeInit.h:65
static float * VAD
Definition: iCub_Sim.cpp:60
static int width_left
Definition: iCub_Sim.cpp:89
virtual void sendTouchRightHand(yarp::os::Bottle &report)=0
static int mouse1_down_y
Definition: iCub_Sim.cpp:57
#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:76
bool sync
Definition: OdeInit.h:69
dSpaceID body_geom_space_id
Definition: OdeInit.h:77
iCub::iKin::iCubArm iKinRightArm
Definition: iCub.h:271
dBodyID inertialBody
Definition: iCub.h:96
static dJointFeedback touchSensorFeedbacks[MAX_DJOINT_FEEDBACKSTRUCTS]
Definition: iCub_Sim.cpp:109
OdeSdlSimulation()
Constructor.
Definition: iCub_Sim.cpp:1309
void DrawVideo(VideoTexture *video)
Definition: rendering.cpp:455
virtual void sendInertial(yarp::os::Bottle &report)=0
void getSkinAndBodyPartFromSpaceAndGeomID(const dSpaceID geomSpaceID, const dGeomID geomID, SkinPart &skinPart, BodyPart &bodyPart, bool &skinCoverFlag)
Definition: iCub.cpp:4174
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:75
virtual void checkTorques()=0
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:86
static int height_right
Definition: iCub_Sim.cpp:92
dSpaceID iCubRightArmSpace
Definition: iCub.h:89
static double dstep
Definition: iCub_Sim.cpp:36
ICubSim * _iCub
Definition: OdeInit.h:66
static float zoom
Definition: iCub_Sim.cpp:71
static VideoTexture * video
Definition: iCub_Sim.cpp:82
virtual bool shouldSendTouchLeftForearm()=0
static long ode_step_length
Definition: iCub_Sim.cpp:35
void setName(string module)
dBodyID l_hand
Definition: iCub.h:163
const dReal * pos
Definition: iCub_Sim.cpp:62
static float view2_hpr[3]
Definition: iCub_Sim.cpp:70
dSpaceID iCubLeftArmSpace
Definition: iCub.h:89
static int stop
Definition: iCub_Sim.cpp:41
dBodyID r_hand
Definition: iCub.h:163
static float ydistance
Definition: iCub_Sim.cpp:65
zeros(2, 2) eye(2
string getName()
Definition: OdeInit.h:88
dWorldID world
Definition: OdeInit.h:57
static float ypos
Definition: iCub_Sim.cpp:72
Matrix H_r2w
Definition: iCub.h:284
static float angle
Definition: iCub_Sim.cpp:72
ConstString actSkinEmul
Definition: iCub.h:80
bool add(const char *port, int textureIndex)
Definition: VideoTexture.h:78
static float yrot
Definition: iCub_Sim.cpp:72
static float zrot
Definition: iCub_Sim.cpp:72
static RobotStreamer * robot_streamer
Definition: iCub_Sim.cpp:83
yarp::os::ConstString texture
Definition: world.h:295
static int cameraSizeWidth
Definition: iCub_Sim.cpp:97
static double frames
Definition: iCub_Sim.cpp:76
Semaphore ODE_access(1)
list< contactOnSkin_t > listOfSkinContactInfos
Definition: OdeInit.h:82
ConstString actCoversCol
Definition: iCub.h:80
#define MAX_DJOINT_FEEDBACKSTRUCTS
Definition: iCub_Sim.cpp:107
int modelTexture[100]
Definition: world.h:261
virtual bool shouldSendTouchLeftArm()=0
static int width
Definition: iCub_Sim.cpp:53
static float view_xyz[3]
Definition: iCub_Sim.cpp:67
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:74
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:1237
tuple name
Definition: manager.py:710
Bottle fullSkinActivationUpperArm
Definition: iCub.h:280
dSpaceID space
Definition: OdeInit.h:58
static float xrot
Definition: iCub_Sim.cpp:72
iCubSimulationControl ** _controls
Definition: OdeInit.h:72
virtual void sendTouchTorso(yarp::os::Bottle &report)=0
virtual bool shouldSendSkinEvents()=0
static double seconds
Definition: iCub_Sim.cpp:76
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:69
dSpaceID iCubLegsSpace
Definition: iCub.h:89
static int v
Definition: iCub_Sim.cpp:42
static float xrotrad
Definition: iCub_Sim.cpp:74
void sendHomePos()
Definition: OdeInit.cpp:125
static OdeInit & get()
Definition: OdeInit.cpp:162
virtual void sendTouchRightForearm(yarp::os::Bottle &report)=0
static bool picking
Definition: iCub_Sim.cpp:50
static long gl_frame_length
Definition: iCub_Sim.cpp:34
Bottle fullSkinActivationForearm
Definition: iCub.h:279
static long finishTime
Definition: iCub_Sim.cpp:75
static const int TORSO_DOF
Definition: common.h:194
static int height
Definition: iCub_Sim.cpp:54
dJointID contact_joint
Definition: OdeInit.h:80
Bottle emptySkinActivationForearm
Definition: iCub.h:276
static bool extractImages
Definition: iCub_Sim.cpp:81
virtual int getWorldTimestep()=0
static int mouse0_down_x
Definition: iCub_Sim.cpp:56
This file is responsible for the initialisation of the world parameters that are controlled by ODE...
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:110
static float lastx
Definition: iCub_Sim.cpp:73
virtual bool getImage(yarp::sig::ImageOf< yarp::sig::PixelRgb > &target)
Definition: iCub_Sim.cpp:1400
ConstString actTorso
Definition: iCub.h:80
static double FPS
Definition: iCub_Sim.cpp:76
static float zpos
Definition: iCub_Sim.cpp:72
static int mouse0_down_y
Definition: iCub_Sim.cpp:57
Bottle emptySkinActivationHand
Definition: iCub.h:275
void draw()
Definition: world.cpp:62
#define CTRL_RAD2DEG
Definition: iCub_Sim.cpp:29
Bottle emptySkinActivationUpperArm
Definition: iCub.h:277
void clearBuffer()
Signal that we're done with a view.
Definition: iCub_Sim.cpp:1305
dGeomID inertialGeom
Definition: iCub.h:97
static float test[3]
Definition: iCub_Sim.cpp:77
double torqueData[100]
Definition: iCub.h:237
void simLoop(int h, int w)
Run the simulation.
Definition: iCub_Sim.cpp:1138
static Uint32 colorkey
Definition: iCub_Sim.cpp:79
static float xpos
Definition: iCub_Sim.cpp:72
virtual void sendTouchLeftHand(yarp::os::Bottle &report)=0
static float xdistance
Definition: iCub_Sim.cpp:66
static bool simrun
Definition: iCub_Sim.cpp:39
#define MY_VERBOSITY
Definition: iCub_Sim.h:61
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:63
dContactGeom contact_geom
Definition: OdeInit.h:79
static int contactPoint
Definition: iCub_Sim.cpp:48
void setJointControlAction()
Set the control action for all the joints, that can be either a velocity command or a torque command...
Definition: iCub.cpp:190
dGeomID Leye1_geom
Definition: iCub.h:177
~OdeSdlSimulation()
Destructor.
Definition: iCub_Sim.cpp:1375
static float view_hpr[3]
Definition: iCub_Sim.cpp:68
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:61
static bool glrun
Definition: iCub_Sim.cpp:38
ConstString actRArm
Definition: iCub.h:80
ConstString actStartHomePos
Definition: iCub.h:80
static double fov_right
Definition: iCub_Sim.cpp:94
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:76
dSpaceID iCub
Definition: iCub.h:88
bool checkSync(bool reset=false)
Definition: iCub_Sim.cpp:1380
bool stop
Definition: OdeInit.h:68
static int width_right
Definition: iCub_Sim.cpp:90
virtual bool shouldSendTouchLeftHand()=0
static int mouse_ray_x
Definition: iCub_Sim.cpp:58
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:91
static int mouse_ray_y
Definition: iCub_Sim.cpp:59
static int mouse1_down_x
Definition: iCub_Sim.cpp:56
static int cameraSizeHeight
Definition: iCub_Sim.cpp:98
#define PART_HEAD
dBodyID lhandfingers3
Definition: iCub.h:133
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:93
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:316
static float angle_yref
Definition: iCub_Sim.cpp:64
static float xyz[3]
Definition: iCub_Sim.cpp:44
static float cam_rx
Definition: iCub_Sim.cpp:51
void sighandler(int sig)
Definition: main_window.cpp:37
Definition: main.cpp:145
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:1312
std::map< dGeomID, string > dGeomNames
Definition: iCub.h:92
static float cam_ry
Definition: iCub_Sim.cpp:51
yarp::sig::Matrix SE3inv(const yarp::sig::Matrix &H, unsigned int verbose=0)
Returns the inverse of a 4 by 4 rototranslational matrix.
ConstString actLArm
Definition: iCub.h:80
static bool START_SELF_COLLISION_DETECTION
Definition: iCub_Sim.cpp:112
yarp::sig::Vector setAng(const yarp::sig::Vector &q)
Sets the free joint angles to values of q[i].
static int mouseDiffx
Definition: iCub_Sim.cpp:49
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:140
virtual void sendVision()=0
Bottle emptySkinActivationTorso
Definition: iCub.h:278
static float rez[3]
Definition: iCub_Sim.cpp:46
dSpaceID iCubTorsoSpace
Definition: iCub.h:89