bool PtzCameraExample::init()
{
  // If the server has the "getCameraList" request, then it's using
  // ArServerHandlerCameraCollection, and migth have multiple PTZs/cameras each with
  // its own set of requests. So send a "getCameraList" request, and when its
  // reply is received, the handler will send "getCameraInfo" requests for each.
  // If the server does not have "getCameraList", it only has one PTZ camera, just
  // send "getCameraInfo". The handler for that will send various control
  // commands.
  // If the server does not have "getCameraInfo", then it doesn't provide any
  // access to PTZ cameras.
  if(myClient->dataExists("getCameraList"))
  {
    ArLog::log(ArLog::Normal, "Server may have multiple cameras. Requesting list.");
    myClient->addHandler("getCameraList", &myCameraListReplyFunc);
    myClient->requestOnce("getCameraList");
  }
  else if(myClient->dataExists("getCameraInfo"))
  {
    ArLog::log(ArLog::Normal, "Server does not support multiple cameras. Requesting info for its camera.");
    ArClientHandlerCamera *camClient = new ArClientHandlerCamera(myClient, "");
    camClient->requestUpdates(100);
    mutex.lock();
    myCameras.insert(camClient);
    mutex.unlock();
  }
  else
  {
    ArLog::log(ArLog::Terse, "Error, server does not have any camera control requests. (Was the server run with video features enabled or video forwarding active?)");
    return false;
  }
  return true;
}
int main(int argc, char **argv)
{
	ros::init(argc, argv, "ariaClientDriverNode");	//ROS Initialization


	Aria::init();										//Aria Initialization
	ArClientBase client;								//setup client
	ArArgumentParser parser(&argc, argv);				//command line argument handler
	ArClientSimpleConnector clientConnector(&parser);	//connect to Arserver

	parser.loadDefaultArguments();
	if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed())
	{
		Aria::logOptions();
		exit(0);
	}

	if (!clientConnector.connectClient(&client))
	{
		if (client.wasRejected())
			printf("Server '%s' rejected connection, exiting\n", client.getHost());
		else
			printf("Could not connect to server '%s', exiting\n", client.getHost());
		exit(1);
	}
	printf("Connected to server.\n");

	client.setRobotName(client.getHost()); // include server name in log messages
	ArKeyHandler keyHandler;
	Aria::setKeyHandler(&keyHandler);
	ArGlobalFunctor escapeCB(&escape);
	keyHandler.addKeyHandler(ArKeyHandler::ESCAPE, &escapeCB);
	client.runAsync();

	if(!client.dataExists("ratioDrive") )
		printf("Warning: server does not have ratioDrive command, can not use drive commands!\n");
	else
		printf("Keys are:\nUP: Forward\nDOWN: Backward\nLEFT: Turn Left\nRIGHT: Turn Right\n");
	printf("s: Enable safe drive mode (if supported).\nu: Disable safe drive mode (if supported).\nl: list all data requests on server\n\nDrive commands use 'ratioDrive'.\nt: logs the network tracking tersely\nv: logs the network tracking verbosely\nr: resets the network tracking\n\n");


	AriaClientDriver ariaClientDriver(&client,&keyHandler,"");

	//while (ros::ok() && client.getRunningWithLock()) //the main loop
	while (client.getRunningWithLock()) //the main loop
	{
		keyHandler.checkKeys();  //addthis if teleop from node required
		ariaClientDriver.controlloop();
		//Input output handling callback threads implemented in ariaClientDriver Class
		ArUtil::sleep(100);	//noneed

	}

	client.disconnect();
	Aria::shutdown();
	return 0;
}
Beispiel #3
0
void InputHandler::sendInput(void)
{
  /* This method is called by the main function to send a ratioDrive
   * request with our current velocity values. If the server does 
   * not support the ratioDrive request, then we abort now: */
  if(!myClient->dataExists("ratioDrive")) return;

  /* Construct a ratioDrive request packet.  It consists
   * of three doubles: translation ratio, rotation ratio, and an overall scaling
   * factor. */
  ArNetPacket packet;
  packet.doubleToBuf(myTransRatio);
  packet.doubleToBuf(myRotRatio);
  packet.doubleToBuf(50); // use half of the robot's maximum.
  packet.doubleToBuf(myLatRatio);
  if (myPrinting)
    printf("Sending\n");
  myClient->requestOnce("ratioDrive", &packet);
  myTransRatio = 0;
  myRotRatio = 0;
  myLatRatio = 0;
}
Beispiel #4
0
int main(int argc, char **argv)
{
  /* Aria initialization: */
  Aria::init();

  //ArLog::init(ArLog::StdErr, ArLog::Verbose);
 

  /* Create our client object. This is the object which connects with a remote
   * server over the network, and which manages all of our communication with it
   * once connected by sending data "requests".  Requests may be sent once, or
   * may be repeated at any frequency. Requests and replies to requsets contain 
   * payload "packets", into which various data types may be packed (when making a 
   * request), and from which they may also be extracted (when handling a reply). 
   * See the InputHandler and OutputHandler classes above for
   * examples of making requests and reading/writing the data in packets.
   */
  ArClientBase client;

  /* Aria components use this to get options off the command line: */
  ArArgumentParser parser(&argc, argv);

  /* This will be used to connect our client to the server, including
   * various bits of handshaking (e.g. sending a password, retrieving a list
   * of data requests and commands...)
   * It will get the hostname from the -host command line argument: */
  ArClientSimpleConnector clientConnector(&parser);

  parser.loadDefaultArguments();

  /* Check for -help, and unhandled arguments: */
  if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed())
  {
    Aria::logOptions();
    exit(0);
  }

  
  /* Connect our client object to the remote server: */
  if (!clientConnector.connectClient(&client))
  {
    if (client.wasRejected())
      printf("Server '%s' rejected connection, exiting\n", client.getHost());
    else
      printf("Could not connect to server '%s', exiting\n", client.getHost());
    exit(1);
  } 

  printf("Connected to server.\n");

  client.setRobotName(client.getHost()); // include server name in log messages

  /* Create a key handler and also tell Aria about it */
  ArKeyHandler keyHandler;
  Aria::setKeyHandler(&keyHandler);

  /* Global escape-key handler to shut everythnig down */
  ArGlobalFunctor escapeCB(&escape);
  keyHandler.addKeyHandler(ArKeyHandler::ESCAPE, &escapeCB);

  /* Now that we're connected, we can run the client in a background thread, 
   * sending requests and receiving replies. When a reply to a request arrives,
   * or the server makes a request of the client, a handler functor is invoked. 
   * The handlers for this program are registered with the client by the 
   * InputHandler and OutputHandler classes (in their constructors, above) */
  client.runAsync();

  /* Create the InputHandler object and request safe-drive mode */
  InputHandler inputHandler(&client, &keyHandler);
  inputHandler.safeDrive();

  /* Use ArClientBase::dataExists() to see if the "ratioDrive" request is available on the 
   * currently connected server.  */
  if(!client.dataExists("ratioDrive") )
      printf("Warning: server does not have ratioDrive command, can not use drive commands!\n");
  else
    printf("Keys are:\nUP: Forward\nDOWN: Backward\nLEFT: Turn Left\nRIGHT: Turn Right\n");
  printf("s: Enable safe drive mode (if supported).\nu: Disable safe drive mode (if supported).\nl: list all data requests on server\n\nDrive commands use 'ratioDrive'.\nt: logs the network tracking tersely\nv: logs the network tracking verbosely\nr: resets the network tracking\n\n");


  /* Create the OutputHandler object. It will begin printing out data from the
   * server. */
  OutputHandler outputHandler(&client);


  /* Begin capturing keys into the key handler. Callbacks will be called
   * asyncrosously from this main thread when pressed.  */

  /* While the client is still running (getRunningWithLock locks the "running"
   * flag until it returns), check keys on the key handler (which will call
   * our callbacks), then tell the input handler to send drive commands. 
   * Sleep a fraction of a second as well to avoid using
   * too much CPU time, and give other threads time to work.
   */
  while (client.getRunningWithLock())
  {
    keyHandler.checkKeys();
    inputHandler.sendInput();
    ArUtil::sleep(100);
  }

  /* The client stopped running, due to disconnection from the server, general
   * Aria shutdown, or some other reason. */
  client.disconnect();
  Aria::shutdown();
  return 0;
}
Beispiel #5
0
int main(int argc, char **argv)
{
  // Initialize Aria and Arnl global information
 
 /* Aria initialization: */
  Aria::init();

  ArLog::init(ArLog::File, ArLog::Verbose,"c:\\temp\\AmbifluxRobot.log",true);

  ArLog::log(ArLog::Verbose, "Ambiflux Starting");

  // Create the sound queue.
  ArSoundsQueue soundQueue;

  // Set WAV file callbacks 
  soundQueue.setPlayWavFileCallback(ArSoundPlayer::getPlayWavFileCallback());
  soundQueue.setInterruptWavFileCallback(ArSoundPlayer::getStopPlayingCallback());

  // Notifications when the queue goes empty or non-empty.
  soundQueue.addQueueEmptyCallback(new ArGlobalFunctor(&queueNowEmpty));
  soundQueue.addQueueNonemptyCallback(new ArGlobalFunctor(&queueNowNonempty));

  // Run the sound queue in a new thread
  soundQueue.runAsync();
  /* Pool de messages en provenance de la tablette
  Issu de l'implementation d'un modèle producteur/consommateur
  pour les messages entrants. Plusieurs thread y accèdent
  Tread-safe (mutex)*/
  //Pool<Frame> messagePool;
 /* Pool de messages en provenance d'un client TCP
  Issu de l'implementation d'un modèle producteur/consommateur
  pour les messages entrants. Plusieurs thread y accèdent
  Tread-safe (mutex)*/
  /*TODO : A remplacer par tcpReceivedPool */
  //Pool<Frame> tcpMessagePool;

  /* Pool de messages en provenance d'un client TCP
  Issu de l'implementation d'un modèle producteur/consommateur
  pour les messages entrants. Plusieurs thread y accèdent
  Tread-safe (mutex)*/
  Pool<TCPReceivedRequest> tcpReceivedPool;

  /*Create our thread to communicate with iPad
   Server start on port 7171 to receive requests from ipad
   A client is created on port 7474 to request iPad
   */
  //IhmCommunicationThread ihm(7171, &messagePool);

  IhmCommunicationThread ihm(7171, &tcpReceivedPool);
   //On s'abonne à la réception de message par la classe IhmCommunicationThread
  //Todo : A supprimer ?
  //ArGlobalFunctor1<Frame> functMessageReceived(&CallbackIhmReceived);
  //ihm.setCallback(&functMessageReceived);
  ihm.runAsync();

  //soundQueue.play("c:\\temp\\let_me_out.wav");

  

  //while(true);

  /* Create our client object. This is the object which connects with a remote
   * server over the network, and which manages all of our communication with it
   * once connected by sending data "requests".  Requests may be sent once, or
   * may be repeated at any frequency. Requests and replies to requsets contain 
   * payload "packets", into which various data types may be packed (when making a 
   * request), and from which they may also be extracted (when handling a reply). 
   * See the InputHandler and OutputHandler classes above for
   * examples of making requests and reading/writing the data in packets.
   */
  ArClientBase client;

  /* Aria components use this to get options off the command line: */
  ArArgumentParser parser(&argc, argv);

  /* This will be used to connect our client to the server, including
   * various bits of handshaking (e.g. sending a password, retrieving a list
   * of data requests and commands...)
   * It will get the hostname from the -host command line argument: */
  ArClientSimpleConnector clientConnector(&parser);

  parser.loadDefaultArguments();

  /* Check for -help, and unhandled arguments: */
  if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed())
  {
    Aria::logOptions();
    exit(0);
  }
  
  /* Connect our client object to the remote server: */
  if (!clientConnector.connectClient(&client))
  {
    if (client.wasRejected())
      printf("Server '%s' rejected connection, exiting\n", client.getHost());
    else
      printf("Could not connect to server '%s', exiting\n", client.getHost());
    exit(1);
  } 

  printf("Connected to server.\n");

  client.setRobotName(client.getHost()); // include server name in log messages


  ///* Create a key handler and also tell Aria about it */
  ArKeyHandler keyHandler;
  Aria::setKeyHandler(&keyHandler);

  /* Global escape-key handler to shut everythnig down */
  ArGlobalFunctor escapeCB(&escape);
  keyHandler.addKeyHandler(ArKeyHandler::ESCAPE, &escapeCB);

  /* Now that we're connected, we can run the client in a background thread, 
   * sending requests and receiving replies. When a reply to a request arrives,
   * or the server makes a request of the client, a handler functor is invoked. 
   * The handlers for this program are registered with the client by the 
   * InputHandler and OutputHandler classes (in their constructors, above) */
  client.runAsync();

  ///* Create the InputHandler object and request safe-drive mode */
  //InputHandler inputHandler(&client);
  //inputHandler.gotoGoal("215");
  ////inputHandler.safeDrive();
  

// Mode goto
if(!client.dataExists("gotoGoal") )
      printf("Warning: Pas de mode goto!\n");
  else
    printf("Mode goto accepte");


//ArFunctor1<ArNetPacket*>
//client.addHandler("pathPlannerStatus",);



  /* Create the OutputHandler object. It will begin printing out data from the
   * server. */
  OutputHandler outputHandler(&client);

   //On s'abonne à la réception de message par la classe IhmCommunicationThread
  //Todo : A supprimer ?
  //ArGlobalFunctor1<Frame> functMessageReceived(&CallbackIhmReceived);
  //ihm.setCallback(&functMessageReceived);
  //ihm.runAsync();

  //pour tester IHM
 // ArUtil::sleep(1000);
//  ihm.testCommunication();

	//SRMA object
	string strSRMA = DALRest::getResourceById("9");
	SRMA srma(strSRMA,client, outputHandler, ihm, &soundQueue);

	//Loop du mode Ambiant
	MainLoop myLoop(srma, &tcpReceivedPool);
	myLoop.runAsync();
	
	//Thread loop : TCP commands
	//Produces messages in tcpMessagePool
	//ServerLoop myServerLoop(srma, &tcpReceivedPool);
	//myServerLoop.runAsync();
 
	//Traitement des requetes TCP
	//Consulmes messages in tcpMessagePool
	//TCPRequestsLoop myTCPRequestsLoop(srma, &tcpReceivedPool);
	//myTCPRequestsLoop.runAsync();

 

  /* While the client is still running (getRunningWithLock locks the "running"
   * flag until it returns), check keys on the key handler (which will call
   * our callbacks), then tell the input handler to send drive commands. 
   * Sleep a fraction of a second as well to avoid using
   * too much CPU time, and give other threads time to work.
   */
  while (client.getRunningWithLock())
  {
    //keyHandler.checkKeys();
    //inputHandler.sendInput();
    ArUtil::sleep(100);
  }

  /* The client stopped running, due to disconnection from the server, general
   * Aria shutdown, or some other reason. */
  client.disconnect();
  Aria::shutdown();
  return 0;
}
Beispiel #6
0
void NavigationClient::Main()
{

	std::cout << "Navigation client started" << std::endl;
	int argsNumber;
	argsNumber = 3;
    char *arguments[argsNumber];
    arguments[0]="./arg_test";
    arguments[1]="-host";
    //arguments[2]="10.41.42.1";
    //se puede poner también patrolbot
    arguments[2]="77.7.27.1";

  int robotCase, counter;
	
  ArClientBase client;
  ArPose pose(0, 0, 0);
  ArPose GoToPose(3000.0, 0.0, -90.0);
  ArNetPacket posePacket, directGoToPosePacket;

  ArArgumentParser parser(&argsNumber, arguments);posePacket.empty();
		 
  ArClientSimpleConnector clientConnector(&parser);
  parser.loadDefaultArguments();
  
  headingsForBedroom.push_back(45);
  headingsForBedroom.push_back(25);
  headingsForBedroom.push_back(0);
  
 
  headingsForLiving.push_back(-20);
  headingsForLiving.push_back(-55);
  headingsForLiving.push_back(-80);
  headingsForLiving.push_back(-110);
  headingsForLiving.push_back(-140);
  
  openDoor = false;
  if (!clientConnector.parseArgs() || !parser.checkHelpAndWarnUnparsed()) {
    clientConnector.logOptions();
    exit(0);
  }
  
  printf("Connecting...\n");
  if (!clientConnector.connectClient(&client)) {
    if (client.wasRejected())
      printf("Server rejected connection, exiting\n");
    else
      printf("Could not connect to server, exiting\n");
    
    exit(1);
  } 

  printf("Connected to server.\n");
  client.addHandler("pathPlannerStatus", new ArGlobalFunctor1<ArNetPacket*>(&handlePathPlannerStatus));
  client.addHandler("update", new ArGlobalFunctor1<ArNetPacket*>(&handleRobotUpdate));
  client.addHandler("goalName", new ArGlobalFunctor1<ArNetPacket*>(&handleGoalName));
  client.addHandler("getGoals", new  ArGlobalFunctor1<ArNetPacket*>(&handleGoalList));
  client.addHandler("getSensorCurrent", new ArGlobalFunctor1<ArNetPacket*>(&handleSensorCurrent));
  client.addHandler("getSensorList", new ArGlobalFunctor1<ArNetPacket*>(&handleSensorList));
  client.addHandler("getLocState", new ArGlobalFunctor1<ArNetPacket*>(&handleLocState));

  client.runAsync();

  client.requestOnce("getGoals");
  client.requestOnce("getSensorList");
  client.requestOnceWithString("getSensorCurrent", "lms2xx_1");
  // client.request("pathPlannerStatus", 5000);
  client.request("goalName", 1000);
  client.request("update", 1000);
  client.requestOnce("getLocState");
  
  sleep(2);
  int cont =0;
  while (!openDoor) {
    cont++;
    ArUtil::sleep(2000);
    client.requestOnceWithString("getSensorCurrent", "lms2xx_1");
  }

  printf("*** Door has been OPENED *** \n");
  sleep(2);

  if (client.dataExists("localizeToPose")) {
	  printf(".. Server does have \"localizeToPose\" request.\n");
	  posePacket.byte4ToBuf(sharedMemory->getInstance().getLocalizationRobotPosition().get_X());
	  posePacket.byte4ToBuf(sharedMemory->getInstance().getLocalizationRobotPosition().get_Y());
	  posePacket.byte4ToBuf(sharedMemory->getInstance().getLocalizationRobotPosition().get_Angle());
	  
	  client.requestOnce("localizeToPose", &posePacket);
	  ArUtil::sleep(1500);
  }
  else
	  printf(".. Server doesn't have that request.\n");

  
  for(;;){
		string action = sharedMemory->getInstance().getAction();
			
		if (action=="navigate"){
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
                   sharedMemory->getInstance().setAction("turn");
		 
			
		}if (action=="navigateToParty"){
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		    sleep(6);
		    sharedMemory->getInstance().startDownToRotations=false;
		    sharedMemory->getInstance().sintetizer.set_Phrase("If you need something please wave your hand to my bottom kinect");
		    sleep(8);
		    indexHeading=0;
		    sharedMemory->getInstance().setAction("turn");
		   
		}
		else if (action=="navigateBackToEmergency"){
		    
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    
		    navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		     // sharedMemory->sintetizer.set_Phrase("Emergency Situation resolved");
		    sharedMemory->getInstance().setAction("createReport");
			
		}else if (action=="navigateToEntrance"){
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    sharedMemory->getInstance().sintetizer.set_Phrase("Do not worry, I have called the ambulance");
			  sleep(2);
		    sharedMemory->getInstance().sintetizer.set_Phrase("Please wait a moment, I willl wait for them");
			  sleep(2);
	  
		    navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		    sharedMemory->getInstance().setAction("waitForAmbulance");
		}
		else if (action=="navigateCloseTo"){
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
	            sharedMemory->getInstance().setAction("requestEmergencyObjects");
			
		}
		else if (action=="navigateToHome"){
		  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
		  navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		  sharedMemory->getInstance().setAction("requestCommand");
		}
		else if (action=="navigateToQuestions"){
		  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
		  navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		  sharedMemory->getInstance().setAction("requestQuestions");
		}
		else if (action=="navigateToObject"){
		  //solo es utilizado por cocktail Party
		  //Si se quita la indicación de lugar en requestOptions aqui debe mandarse el destino predefinido (kitchen?)
		  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
		  navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		  sharedMemory->getInstance().setAction("recognizeObject");
		}
		else if (action=="navigateToObjectCategory"){
		  //considera que la posición de la categoria de un objeto (en pick and place) es la misma posición que la de donde esta el objeto en emergencia.
		  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl; 
		  //por default ahorita esta dining como el la categoria del objeto
		  navigateTo(sharedMemory->getInstance().getStringDestination(), &client);
		  if (sharedMemory->getInstance().getTestRunning()=="pick and place" || sharedMemory->getInstance().getTestRunning()=="Emergency" )
		    sharedMemory->getInstance().setAction("deliverObject");
		  else
		  sharedMemory->getInstance().setAction("userRecognize");
			
		}else if (action=="navigateToPoint"){
		    
		    cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
		    //TODO verificar que esto limpia el objeto
		    posePacket.empty();
		    posePacket.byte4ToBuf(sharedMemory->getInstance().lastObjective->getObjetivePosition().get_X());
		    posePacket.byte4ToBuf(sharedMemory->getInstance().lastObjective->getObjetivePosition().get_Y());
		    posePacket.byte4ToBuf(sharedMemory->getInstance().lastObjective->getObjetivePosition().get_Angle());
		    cout << "Enviando punto a navegación: "<< sharedMemory->getInstance().lastObjective->getObjetivePosition().get_X() << "," << sharedMemory->getInstance().lastObjective->getObjetivePosition().get_Y() << "," << sharedMemory->getInstance().lastObjective->getObjetivePosition().get_Angle()<<endl;
		    client.requestOnce("gotoPose", &posePacket);
		  
		    sleep(10);
		    printf("Before while Navigation");
		    while (strncmp(textData, "Arrived at", 10) != 0){
			sleep(10);
		    }
		 
		    printf("Navigation ended");
	           if (sharedMemory->getInstance().getTestRunning()=="CocktailParty")
		   sharedMemory->getInstance().setAction("userLearn");
		   else
		   sharedMemory->getInstance().setAction("requestEmergencyObjects");
	
		}else if (action=="navigateForward"){
		  
		  stringstream command;
		  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
		  command<<"8 " << sharedMemory->getInstance().getGestureDepthPosition();
		  cout<< "******  AVANZA "<<command.str().c_str()<<" mm"<<endl;
		  client.requestOnceWithString("MicroControllerMotionCommand",command.str().c_str());
		  sleep(10);
		  printf("Before while Navigation");
		  while (strncmp(textData, "Stopped", 10) != 0){
			sleep(10);
			
		  }
		  sharedMemory->getInstance().setAction("turn");
		}else if (action=="turn"){
		  
		  int heading=0;
		  stringstream command;
                  cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;
		  if (sharedMemory->getInstance().startDownToRotations==false){
		    if (sharedMemory->getInstance().getStringDestination()=="bedroom"){
		      cout<<"Entrando BEDROOM 1"<<endl;
		      if (indexHeading < headingsForBedroom.size()){
			heading=headingsForBedroom[indexHeading];
			indexHeading++;
			cout<<"Entrando a If UNO bedroom"<<endl;
		      }else{
			sharedMemory->getInstance().startDownToRotations=true;
			indexHeading=headingsForBedroom.size()-2;
			heading=(-1000);//valor dado para detectar que no se obtuvo un valor válido para el heading, dado que se cambia la forma en como se recorre el arreglo
			cout<<"Entrando a else UNO bedroom"<<endl;
		      }
		    }else {//if (sharedMemory->getInstance().getStringDestination()=="living"){
		      cout<<"Entrando a LIVING 1"<<endl;
		      if (indexHeading < headingsForLiving.size()){
			heading=headingsForLiving[indexHeading];
			indexHeading++;
			cout<<"Entrando a If UNO living"<<endl;
		      }else{
			sharedMemory->getInstance().startDownToRotations=true;
			indexHeading=headingsForLiving.size()-2;//no menos uno porque ya el proceso anterior permition visitar este indice
			heading=(-1000);
			cout<<"Entrando a else UNO Living"<<endl;
		      }
		    }
		    
		  }else{
		    if (sharedMemory->getInstance().getStringDestination()=="bedroom"){
		      cout<<"Entrando BEDROoM 2"<<endl;
		      if (indexHeading >= 0){
			heading=headingsForBedroom[indexHeading];
			indexHeading--;
			cout<<"Entrando a if DOS bedroom"<<endl;
		      }else{
			sharedMemory->getInstance().startDownToRotations=false;
			indexHeading=1;
			heading=(-1000);
			cout<<"Entrando a else DOS bedroom"<<endl;
		      }
		    }else {//if (sharedMemory->getInstance().getStringDestination()=="living"){
		      cout<<"Entrando a LIVING 2"<<endl;
		      if (indexHeading>= 0){
			heading=headingsForLiving[indexHeading];
			indexHeading--;
			cout<<"Entrando a if DOS living"<<endl;
		      }else{
			sharedMemory->getInstance().startDownToRotations=false;
			indexHeading=1;//no 0 porque ya el proceso anterior permitió visitar este indice
			heading=(-1000);
			cout<<"Entrando a else DOS living"<<endl;
		      }
		    }
		  }
		    
		  if (heading>(-1000)){
		    command<<"12 " << heading;
		    cout<< "******  ROTAR "<<command.str().c_str()<<" grades con INDEXHEADING: "<<indexHeading<<"valorArray"<< headingsForLiving[indexHeading]<<endl;
		    client.requestOnceWithString("MicroControllerMotionCommand",command.str().c_str());
		    //sharedMemory->getInstance().sintetizer.set_Phrase("If you need something, please wave your hand to my bottom kinect");
	            sleep(1);
		    cout<<"*INVERSA al hacer el heading: "<< sharedMemory->getInstance().startDownToRotations << endl;
		    sharedMemory->getInstance().setAction("payAttention"); 
		  }
		}else if (action=="navigateToExit"){
		    //éste estado solo llamarlo para terminar la prueba
		    cout<<"Starting: "<< action << "STATE in NavigationClient"<<endl;  
		    navigateTo("Exit", &client);
		   sharedMemory->getInstance().setAction("turnOff");;		
		}
		else if (action=="turnOff"){
                       cout<<"Starting: "<< action << " STATE in NavigationClient"<<endl;  
			//ArUtil::sleep(60000);
			printf("Server disconnected.\n");
			Aria::shutdown();
		}
	
	}
	return ;
  
}