Exemplo n.º 1
0
void ArCentralManager::netClientList(ArServerClient *client, ArNetPacket *packet)
{
  ArNetPacket sendPacket;
  std::list<ArCentralForwarder *>::iterator fIt;
  ArCentralForwarder *forwarder;
  ArTypes::UByte2 sizeLen;
  ArTypes::UByte2 realLen;
  unsigned int numConnected = 0;

  myDataMutex.lock();
  sizeLen = sendPacket.getLength();
  sendPacket.uByte2ToBuf(0);
  for (fIt = myForwarders.begin(); fIt != myForwarders.end(); fIt++)
  {
    forwarder = (*fIt);

    if (!forwarder->isConnected())
      continue;

    numConnected++;
    sendPacket.strToBuf("");
    sendPacket.uByte2ToBuf(forwarder->getPort());
    sendPacket.strToBuf(forwarder->getRobotName());
    sendPacket.strToBuf("");
    sendPacket.strToBuf(
	    forwarder->getClient()->getTcpSocket()->getIPString());
  }

  realLen = sendPacket.getLength();
  sendPacket.setLength(sizeLen);
  sendPacket.uByte2ToBuf(numConnected);
  sendPacket.setLength(realLen);

  myDataMutex.unlock();
  client->sendPacketTcp(&sendPacket);
}
AREXPORT void ArServerHandlerCamera::handleGetCameraModeList(
	ArServerClient *client, ArNetPacket *packet)
{
  ArNetPacket sending;

  myModeMutex.lock();
  sending.uByte2ToBuf(myCameraModeNameMap.size());

  std::map<CameraMode, std::string>::iterator it;
  for (it = myCameraModeNameMap.begin(); it != myCameraModeNameMap.end(); it++)
  {
    sending.strToBuf((*it).second.c_str());
  }
  myModeMutex.unlock();
  client->sendPacketTcp(&sending);
}
Exemplo n.º 3
0
AREXPORT void ArCentralManager::forwarderServerClientRemovedCallback(
	ArCentralForwarder *forwarder, ArServerClient *client)
{
  // if this matches we're already closing this so don't do/print anything
  if (myClosingConnectionID != 0 && 
      myClosingConnectionID == client->getIdentifier().getConnectionID())
    return;

  ArLog::log(ArLog::Normal, 
	     "Notifying main server of removal of serverClient for %s %s", 
	     forwarder->getRobotName(), client->getIPString());

  ArNetPacket sendPacket;
  sendPacket.strToBuf("");
  sendPacket.uByte2ToBuf(forwarder->getPort());
  sendPacket.strToBuf(forwarder->getRobotName());
  sendPacket.strToBuf("");
  sendPacket.strToBuf(
	  forwarder->getClient()->getTcpSocket()->getIPString());
  myClientServer->broadcastPacketTcpToMatching(&sendPacket, "clientRemoved",
					       client->getIdentifier(), true);
  myClientServer->broadcastPacketTcpToMatching(&sendPacket, "clientAdded",
					       client->getIdentifier(), true);
}
Exemplo n.º 4
0
/// This should be its own thread here
void *ArCentralManager::runThread(void *arg)
{
  std::list<ArSocket *>::iterator sIt;
  std::list<std::string>::iterator nIt;
  std::list<ArCentralForwarder *>::iterator fIt;
  ArSocket *socket;
  std::string robotName;
  ArCentralForwarder *forwarder;

  ArNetPacket *packet;
  std::list<ArNetPacket *> addPackets;
  std::list<ArNetPacket *> remPackets;


  threadStarted();
  while (getRunning())
  {
    int numForwarders = 0;
    int numClients = 0;
    
    myDataMutex.lock();
    // this is where the original code to add forwarders was before we
    // changed the unique behavior to drop old ones...


    std::list<ArCentralForwarder *> connectedRemoveList;
    std::list<ArCentralForwarder *> unconnectedRemoveList;
    for (fIt = myForwarders.begin(); fIt != myForwarders.end(); fIt++)
    {
      forwarder = (*fIt);

      numForwarders++;
      if (forwarder->getServer() != NULL)
	numClients += forwarder->getServer()->getNumClients();
      bool connected = forwarder->isConnected();
      bool removed = false;
      if (!forwarder->callOnce(myHeartbeatTimeout, myUdpHeartbeatTimeout,
			       myRobotBackupTimeout, myClientBackupTimeout))
      {
	if (connected)
	{
	  ArLog::log(ArLog::Normal, "Will remove forwarder from %s", 
		     forwarder->getRobotName());
	  connectedRemoveList.push_back(forwarder);
	  removed = true;
	}
	else
	{
	  ArLog::log(ArLog::Normal, "Failed to connect to forwarder from %s", 
		     forwarder->getRobotName());
	  unconnectedRemoveList.push_back(forwarder);
	  removed = true;
	}
      }
      if (!connected && !removed && forwarder->isConnected())
      {
	ArLog::log(ArLog::Normal, "Adding forwarder %s", 
		   forwarder->getRobotName());
	ArTime *newTime = new ArTime;
	newTime->setSec(0);
	myUsedPorts[forwarder->getPort()] = newTime;
	
	std::multimap<int, ArFunctor1<ArCentralForwarder *> *>::iterator it;
	for (it = myForwarderAddedCBList.begin();
	     it != myForwarderAddedCBList.end();
	     it++)
	{
	  if ((*it).second->getName() == NULL || 
	      (*it).second->getName()[0] == '\0')
	    ArLog::log(ArLog::Normal, "Calling unnamed add functor at %d",
		       -(*it).first);
	  else
	    ArLog::log(ArLog::Normal, "Calling %s add functor at %d",
		       (*it).second->getName(), -(*it).first);
	  (*it).second->invoke(forwarder);
	}
	ArLog::log(ArLog::Normal, "Added forwarder %s", 
		   forwarder->getRobotName());      
	ArNetPacket *sendPacket = new ArNetPacket;
	sendPacket->strToBuf("");
	sendPacket->uByte2ToBuf(forwarder->getPort());
	sendPacket->strToBuf(forwarder->getRobotName());
	sendPacket->strToBuf("");
	sendPacket->strToBuf(
		forwarder->getClient()->getTcpSocket()->getIPString());
	addPackets.push_back(sendPacket);
	// MPL added this at the same time as the changes for the deadlock that happened down below
	//myClientServer->broadcastPacketTcp(&sendPacket, "clientAdded");
      }
    }

    while ((fIt = connectedRemoveList.begin()) != connectedRemoveList.end())
    {
      forwarder = (*fIt);

      ArLog::log(ArLog::Normal, "Removing forwarder %s", 
		 forwarder->getRobotName());
      std::multimap<int, ArFunctor1<ArCentralForwarder *> *>::iterator it;
      for (it = myForwarderRemovedCBList.begin();
	   it != myForwarderRemovedCBList.end();
	   it++)
      {
	if ((*it).second->getName() == NULL || 
	    (*it).second->getName()[0] == '\0')
	  ArLog::log(ArLog::Normal, "Calling unnamed remove functor at %d",
		     -(*it).first);
	else
	  ArLog::log(ArLog::Normal, "Calling %s remove functor at %d",
		     (*it).second->getName(), -(*it).first);
	(*it).second->invoke(forwarder);
      }

      ArLog::log(ArLog::Normal, "Called forwarder removed for %s", 
		 forwarder->getRobotName());
      ArNetPacket *sendPacket = new ArNetPacket;
      sendPacket->strToBuf("");
      sendPacket->uByte2ToBuf(forwarder->getPort());
      sendPacket->strToBuf(forwarder->getRobotName());
      sendPacket->strToBuf("");
      sendPacket->strToBuf(
	      forwarder->getClient()->getTcpSocket()->getIPString());
      // MPL making this just push packets into a list to broadcast at the end since this was deadlocking
      //myClientServer->broadcastPacketTcp(&sendPacket, "clientRemoved");
      remPackets.push_back(sendPacket);

      if (myUsedPorts.find(forwarder->getPort()) != myUsedPorts.end() && 
	  myUsedPorts[forwarder->getPort()] != NULL)
	myUsedPorts[forwarder->getPort()]->setToNow();

      myForwarders.remove(forwarder);
      delete forwarder;
      connectedRemoveList.pop_front();
      ArLog::log(ArLog::Normal, "Removed forwarder");

    }

    while ((fIt = unconnectedRemoveList.begin()) != 
	   unconnectedRemoveList.end())
    {
      forwarder = (*fIt);
      ArLog::log(ArLog::Normal, "Removing unconnected forwarder %s", 
		 forwarder->getRobotName());

      if (myUsedPorts.find(forwarder->getPort()) != myUsedPorts.end() && 
	  myUsedPorts[forwarder->getPort()] != NULL)
	myUsedPorts[forwarder->getPort()]->setToNow();      

      myForwarders.remove(forwarder);
      delete forwarder;
      unconnectedRemoveList.pop_front();
      ArLog::log(ArLog::Normal, "Removed unconnected forwarder");
    }


    // this code was up above just after the lock before we changed
    // the behavior for unique names
    while ((sIt = myClientSockets.begin()) != myClientSockets.end() && 
	   (nIt = myClientNames.begin()) != myClientNames.end())
    {
      socket = (*sIt);
      robotName = (*nIt);

      myClientSockets.pop_front();
      myClientNames.pop_front();

      ArLog::log(ArLog::Normal, 
		 "New forwarder for socket from %s with name %s", 
		 socket->getIPString(), robotName.c_str());

      forwarder = new ArCentralForwarder(myClientServer, socket, 
					 robotName.c_str(), 
					 myClientServer->getTcpPort() + 1, 
					 &myUsedPorts, 
					 &myForwarderServerClientRemovedCB,
					 myEnforceProtocolVersion.c_str(),
					 myEnforceType);
      myForwarders.push_back(forwarder);
    }

    numClients += myRobotServer->getNumClients();
    if (myRobotServer != myClientServer)
      numClients += myClientServer->getNumClients();
    // end of code moved for change in unique behavior
    if (numClients > myMostClients)
    {
      ArLog::log(ArLog::Normal, "CentralManager: New most clients: %d", 
		 numClients);
      myMostClients = numClients;
    }

    if (numForwarders > myMostForwarders)
      myMostForwarders = numForwarders;

    if (numClients > myMostClients)
    {
      ArLog::log(ArLog::Normal, "CentralManager: New most forwarders: %d", 
		 numForwarders);
      myMostForwarders = numForwarders;
    }

    myRobotServer->internalSetNumClients(numForwarders + 
					 myClientSockets.size());

    myDataMutex.unlock();

    while (addPackets.begin() != addPackets.end())
    {
      packet = addPackets.front();
      myClientServer->broadcastPacketTcp(packet, "clientAdded");
      addPackets.pop_front();
      delete packet;
    }

    while (remPackets.begin() != remPackets.end())
    {
      packet = remPackets.front();
      myClientServer->broadcastPacketTcp(packet, "clientRemoved");
      remPackets.pop_front();
      delete packet;
    }

    ArUtil::sleep(1); 

    //make this a REALLY long sleep to test the duplicate pending
    //connection code
    //ArUtil::sleep(20000);
  }

  threadFinished();
  return NULL;
}
AREXPORT void ArServerHandlerMapping::serverMappingEnd(
	ArServerClient *client, ArNetPacket *packet)
{
  std::list<ArFunctor *>::iterator fit;

  ArNetPacket sendPacket;
  if (myLaserLogger == NULL)
  {
    ArLog::log(ArLog::Normal, "MappingEnd: No map being made");
    sendPacket.byteToBuf(1);
    if (client != NULL)
      client->sendPacketTcp(&sendPacket);
    return;
  }

  myRobot->lock();

  delete myLaserLogger;
  myLaserLogger = NULL;

  bool haveFile2 = false;

  if (myLaserLogger2 != NULL)
  {
    haveFile2 = true;
    delete myLaserLogger2;
    myLaserLogger2 = NULL;
  }
    
    
  std::list<std::string> sourceFileNameList;
  sourceFileNameList.push_back(myFileName);
  if (haveFile2) {
    sourceFileNameList.push_back(myFileName2);
  }

  bool isSuccess = myTempDirectoryHelper.moveFilesToBaseDirectory
                                           (sourceFileNameList);
  
  if (isSuccess) {
    sendPacket.uByte2ToBuf(0);
  }
  else {
    sendPacket.uByte2ToBuf(2);
  } 


  ArLog::log(ArLog::Normal, "MappingEnd: Stopped mapping %s", 
	           myFileName.c_str());

  // call our mapping end callbacks
  for (fit = myMappingEndCallbacks.begin(); 
       fit != myMappingEndCallbacks.end(); 
       fit++)
    (*fit)->invoke();
  
  
  // Call the mapping ended callbacks
  for (fit = myMappingEndedCallbacks.begin(); 
       fit != myMappingEndedCallbacks.end(); 
       fit++) {
    (*fit)->invoke();
  }

  // Clear the internal file names
  myMapName = "";
  myFileName = "";

  myRobot->unlock();
  if (client != NULL)
    client->sendPacketTcp(&sendPacket);

  ArNetPacket broadcastPacket;
  broadcastPacket.strToBuf(myFileName.c_str());
  myServer->broadcastPacketTcp(&broadcastPacket, "mappingStatusBroadcast");
}
AREXPORT ArServerClient::ArServerClient(
	ArSocket *tcpSocket, unsigned int udpPort, long authKey,
	long introKey, 	ArRetFunctor2<bool, ArNetPacket *, 
	struct sockaddr_in *> *sendUdpCallback,
	std::map<unsigned int, ArServerData *> *dataMap,
	const char *passwordKey, const char *serverKey,
	const ArServerUserInfo *userInfo, int rejecting, 
	const char *rejectingString, bool debugLogging,
	const char *serverClientName, bool logPasswordFailureVerbosely,
	bool allowSlowPackets, bool allowIdlePackets) :
  myProcessPacketCB(this, &ArServerClient::processPacket, NULL, true)
{
  ArNetPacket packet;

  // set our default to no command
  pushCommand(0);

  myAuthKey = authKey;
  myIntroKey = introKey;
  myTcpSocket.transfer(tcpSocket);
  myTcpSocket.setCloseCallback(tcpSocket->getCloseCallback());
  myTcpSocket.setNonBlock();
  myTcpReceiver.setSocket(&myTcpSocket);
  myTcpReceiver.setProcessPacketCB(&myProcessPacketCB);
  myTcpSender.setSocket(&myTcpSocket);

  mySendUdpCB = sendUdpCallback;
  myDataMap = dataMap;
  if (udpPort == 0)
    myTcpOnly = true;
  else
    myTcpOnly = false;
  mySentTcpOnly = myTcpOnly;

  myUserInfo = userInfo;
  myPasswordKey = passwordKey;
  myServerKey = serverKey;
  myRejecting = rejecting;
  if (rejectingString != NULL)
    myRejectingString = rejectingString;

  myDebugLogging = debugLogging;
  if (myDebugLogging)
    myVerboseLogLevel = ArLog::Normal;
  else
    myVerboseLogLevel = ArLog::Verbose;

  myTcpSender.setDebugLogging(myDebugLogging);

  myLogPrefix = serverClientName;
  myLogPrefix += ": ";
  myTcpSender.setLoggingPrefix(myLogPrefix.c_str());
  myTcpReceiver.setLoggingPrefix(myLogPrefix.c_str());

  myLogPasswordFailureVerbosely = logPasswordFailureVerbosely;

  mySlowPacketsMutex.setLogName("ArServerClient::mySlowPacketsMutex");
  myIdlePacketsMutex.setLogName("ArServerClient::myIdlePacketsMutex");

  myAllowSlowPackets = allowSlowPackets;
  myAllowIdlePackets = allowIdlePackets;

  setIdentifier(ArServerClientIdentifier());
  internalSwitchState(STATE_SENT_INTRO);

  packet.empty();
  packet.setCommand(ArServerCommands::INTRODUCTION);
  packet.strToBuf("alpha");
  packet.uByte2ToBuf(udpPort);
  packet.uByte4ToBuf(myAuthKey);
  packet.uByte4ToBuf(myIntroKey);
  packet.strToBuf(myPasswordKey.c_str());
  sendPacketTcp(&packet);

  mySlowIdleThread = NULL;

  myHaveSlowPackets = false;
  myHaveIdlePackets = false;
  
  myCreationTime.setToNow();

  resetTracking();
}
void ArServerClient::sendListPacket(void)
{
  ArNetPacket packet;
  std::map<unsigned int, ArServerData *>::iterator it;
  unsigned int count;
  unsigned int shortLen;
  unsigned int longLen;
  ArServerData *serverData;

  // First we send a list of numbers, names and descriptions
  packet.setCommand(ArServerCommands::LIST);
  
  // number of entries (we'll overwrite it later with the right number)
  shortLen = packet.getLength();
  packet.uByte2ToBuf(0);
  // loop through the data to build the packet
  for (it = myDataMap->begin(), count = 0; it != myDataMap->end(); it++)
  {
    serverData = (*it).second;
    if (myUserInfo == NULL || 
	serverData->getCommandGroup() == NULL || 
	serverData->getCommandGroup()[0] == '\0' || 
	myGroups.count(serverData->getCommandGroup()) != 0 || 
	myGroups.count("all") != 0)
    {
      count++;
      packet.uByte2ToBuf(serverData->getCommand());
      packet.strToBuf(serverData->getName());
      packet.strToBuf(serverData->getDescription());
    }
  }
  // put the real number of entries in the right spot 
  longLen = packet.getLength();
  packet.setLength(shortLen);
  packet.uByte2ToBuf(count);
  packet.setLength(longLen);

  sendPacketTcp(&packet);

  // then we send a list of the arguments and returns... they aren't
  // combined so that the packet structure doesn't need to change
  packet.empty();
  packet.setCommand(ArServerCommands::LISTARGRET);
  
  // number of entries (we'll overwrite it later with the right number)
  shortLen = packet.getLength();
  packet.uByte2ToBuf(0);
  
  // loop through the data to build the packet
  for (it = myDataMap->begin(), count = 0; it != myDataMap->end(); it++)
  {
    serverData = (*it).second;
    if (myUserInfo == NULL || 
	serverData->getCommandGroup() == NULL || 
	serverData->getCommandGroup()[0] == '\0' || 
	myGroups.count(serverData->getCommandGroup()) != 0 || 
	myGroups.count("all") != 0)
    {
      count++;
      packet.uByte2ToBuf(serverData->getCommand());
      packet.strToBuf(serverData->getArgumentDescription());
      packet.strToBuf(serverData->getReturnDescription());
    }

  }
  // put the real number of entries in the right spot
  longLen = packet.getLength();
  packet.setLength(shortLen);
  packet.uByte2ToBuf(count);
  packet.setLength(longLen);
  sendPacketTcp(&packet);


  // then we send a list of command groups... they aren't
  // combined so that the packet structure doesn't need to change
  packet.empty();
  packet.setCommand(ArServerCommands::LISTGROUPANDFLAGS);
  
  // number of entries (we'll overwrite it later with the right number)
  shortLen = packet.getLength();
  packet.uByte2ToBuf(0);
  
  // loop through the data to build the packet
  for (it = myDataMap->begin(), count = 0; it != myDataMap->end(); it++)
  {
    serverData = (*it).second;
    if (myUserInfo == NULL || 
	serverData->getCommandGroup() == NULL || 
	serverData->getCommandGroup()[0] == '\0' || 
	myGroups.count(serverData->getCommandGroup()) != 0 || 
	myGroups.count("all") != 0)
    {
      count++;
      packet.uByte2ToBuf(serverData->getCommand());
      packet.strToBuf(serverData->getCommandGroup());
      packet.strToBuf(serverData->getDataFlagsString());
    }

  }
  // put the real number of entries in the right spot
  longLen = packet.getLength();
  packet.setLength(shortLen);
  packet.uByte2ToBuf(count);
  packet.setLength(longLen);
  sendPacketTcp(&packet);
}
Exemplo n.º 8
0
void putFile(char *fileName, char *asFileName)
{
  ArNetPacket sendPacket;
  size_t ui;
  size_t len;

  FILE *file;
  if ((file = ArUtil::fopen(fileName, "r")) == NULL)
  {
    ArLog::log(ArLog::Normal, 
	       "putFile: can't open file '%s'", fileName);
    return;
  }

  // tell the server we're sending
  
  sendPacket.empty();
  sendPacket.uByte2ToBuf(0);
  sendPacket.strToBuf(asFileName);
  client.requestOnce("putFile", &sendPacket);
  printf("Starting send of file %s\n", fileName);
  
  char buf[30000];
  size_t ret;
  // now send the file
  while ((ret = fread(buf, 1, sizeof(buf), file)) == sizeof(buf))
  {
    sendPacket.empty();
    sendPacket.uByte2ToBuf(1);
    sendPacket.strToBuf(asFileName);
    sendPacket.uByte4ToBuf(ret);
    sendPacket.dataToBuf(buf, ret);
    client.requestOnce("putFile", &sendPacket);
    printf("Sent packet with %d\n", ret);
  }
  if (ferror(file))
  {
    ArLog::log(ArLog::Normal, "ArServerFileToClient: Error sending file %s", 
	       fileName);
    sendPacket.empty();
    sendPacket.uByte2ToBuf(3);
    sendPacket.strToBuf(asFileName);
    client.requestOnce("putFile", &sendPacket);
    return;
  }

  sendPacket.empty();
  sendPacket.uByte2ToBuf(1);
  sendPacket.strToBuf(asFileName);
  sendPacket.uByte4ToBuf(ret);
  sendPacket.dataToBuf(buf, ret);
  client.requestOnce("putFile", &sendPacket);
  printf("Sent packet with %d\n", ret);


  sendPacket.empty();
  sendPacket.uByte2ToBuf(2);
  sendPacket.strToBuf(asFileName);
  client.requestOnce("putFile", &sendPacket);

  if (feof(file))
  {
    ArLog::log(ArLog::Normal, "ArServerFileToClient: Sent file %s", fileName);
  }
  
  fclose(file);
}
AREXPORT void ArServerHandlerMapping::serverMappingEnd(
	ArServerClient *client, ArNetPacket *packet)
{
  std::list<ArFunctor *>::iterator fit;

  ArNetPacket sendPacket;
  if (myLaserLogger == NULL)
  {
    ArLog::log(ArLog::Normal, "MappingEnd: No map being made");
    sendPacket.byteToBuf(1);
    if (client != NULL)
      client->sendPacketTcp(&sendPacket);
    return;
  }

  myRobot->lock();
  delete myLaserLogger;
  myLaserLogger = NULL;

  bool haveFile2 = false;

  if (myLaserLogger2 != NULL)
  {
    haveFile2 = true;
    delete myLaserLogger2;
    myLaserLogger2 = NULL;
  }
    
  // now, if our temp directory and base directory are different we
  // need to move it and put the result in the packet, otherwise put
  // in we're okay
  if (ArUtil::strcasecmp(myBaseDirectory, myTempDirectory) != 0)
  {
#ifndef WIN32
    char *mvName = "mv";
#else
    char *mvName = "move";
#endif
    char systemBuf[6400];
    char fromBuf[1024];
    char toBuf[1024];

    char systemBuf2[6400];
    char fromBuf2[1024];
    char toBuf2[1024];

    if (myTempDirectory.size() > 0)
      snprintf(fromBuf, sizeof(fromBuf), "%s%s", 
	       myTempDirectory.c_str(), myFileName.c_str());
    else
      snprintf(fromBuf, sizeof(fromBuf), "%s", myFileName.c_str());
    ArUtil::fixSlashes(fromBuf, sizeof(fromBuf));

    if (myTempDirectory.size() > 0)
      snprintf(toBuf, sizeof(toBuf), "%s%s", 
	       myBaseDirectory.c_str(), myFileName.c_str());
    else
      snprintf(toBuf, sizeof(toBuf), "%s", myFileName.c_str());
    ArUtil::fixSlashes(toBuf, sizeof(toBuf));

    sprintf(systemBuf, "%s \"%s\" \"%s\"", mvName, fromBuf, toBuf);




    ArLog::log(ArLog::Verbose, "Moving with '%s'", systemBuf);
    // call our pre move callbacks
    for (fit = myPreMoveCallbacks.begin(); 
	 fit != myPreMoveCallbacks.end(); 
	 fit++)
      (*fit)->invoke();

    // move file
    int ret;
    if ((ret = system(systemBuf)) == 0)
    {
      ArLog::log(ArLog::Verbose, "ArServerHandlerMapping: Moved file %s (with %s)", 
		 myFileName.c_str(), systemBuf);
      sendPacket.byteToBuf(0);
    }
    else
    {
      ArLog::log(ArLog::Normal, 
		 "ArServerHandlerMapping: Couldn't move file for %s (ret of '%s' is %d) removing file", 
		 myFileName.c_str(), systemBuf, ret);
      unlink(fromBuf);
      sendPacket.uByte2ToBuf(2);
    }

    if (haveFile2)
    {
      if (myTempDirectory.size() > 0)
	snprintf(fromBuf2, sizeof(fromBuf2), "%s%s", 
		 myTempDirectory.c_str(), myFileName2.c_str());
      else
	snprintf(fromBuf2, sizeof(fromBuf2), "%s", myFileName2.c_str());
      ArUtil::fixSlashes(fromBuf2, sizeof(fromBuf2));
      
      if (myTempDirectory.size() > 0)
	snprintf(toBuf2, sizeof(toBuf2), "%s%s", 
		 myBaseDirectory.c_str(), myFileName2.c_str());
      else
	snprintf(toBuf2, sizeof(toBuf2), "%s", myFileName2.c_str());
      ArUtil::fixSlashes(toBuf2, sizeof(toBuf2));
      
      sprintf(systemBuf2, "%s \"%s\" \"%s\"", mvName, fromBuf2, toBuf2);
      
      if ((ret = system(systemBuf2)) == 0)
      {
	ArLog::log(ArLog::Verbose, "ArServerHandlerMapping: Moved file2 %s (with %s)", 
		   myFileName2.c_str(), systemBuf2);
      }
      else
      {
	ArLog::log(ArLog::Normal, 
		   "ArServerHandlerMapping: Couldn't move file2 for %s (ret of '%s' is %d) removing file", 
		   myFileName2.c_str(), systemBuf2, ret);
	unlink(fromBuf2);
      }
    }
    
    // call our post move callbacks
    for (fit = myPostMoveCallbacks.begin(); 
	 fit != myPostMoveCallbacks.end(); 
	 fit++)
      (*fit)->invoke();

  }
  else
  {
    // just put in things are okay, it'll get sent below
    sendPacket.byteToBuf(0);
  }


  ArLog::log(ArLog::Normal, "MappingEnd: Stopped mapping %s", 
	     myFileName.c_str());

  // call our mapping started callbacks
  for (fit = myMappingEndCallbacks.begin(); 
       fit != myMappingEndCallbacks.end(); 
       fit++)
    (*fit)->invoke();

  myMapName = "";
  myFileName = "";

  myRobot->unlock();
  if (client != NULL)
    client->sendPacketTcp(&sendPacket);

  ArNetPacket broadcastPacket;
  broadcastPacket.strToBuf(myFileName.c_str());
  myServer->broadcastPacketTcp(&broadcastPacket, "mappingStatusBroadcast");
}