//NEW LASER DATA REQUESt CAPABILITY
void laserRequest(ArServerClient *client, ArNetPacket *packet)
{ 
  robot.lock();
  ArNetPacket sending;
  sending.empty();
  ArLaser* laser = robot.findLaser(1);
  if(!laser){
      printf("Could not connect to Laser... exiting\n");
      Aria::exit(1);}	
  laser->lockDevice();
  const std::list<ArSensorReading*> *sensorReadings = laser->getRawReadings(); // see ArRangeDevice interface doc
  sending.byte4ToBuf((ArTypes::Byte4)(sensorReadings->size()));
  for (std::list<ArSensorReading*>::const_iterator it2= sensorReadings->begin(); it2 != sensorReadings->end(); ++it2){
	ArSensorReading* laserRead =*it2;
        sending.byte4ToBuf((ArTypes::Byte4)(laserRead->getRange()));
	//printf("%i,%i:",laserRead->getRange(),laserRead->getIgnoreThisReading());
  }
  laser->unlockDevice();
  robot.unlock();
  sending.finalizePacket();
  //sending.printHex();
  client->sendPacketTcp(&sending);
}
AREXPORT void ArServerInfoSensor::getSensorCumulative(ArServerClient *client, 
					ArNetPacket *packet)
{
  ArRangeDevice *dev;
  char sensor[512];
  std::list<ArPoseWithTime *> *readings;
  std::list<ArPoseWithTime *>::iterator it;

  while (packet->getDataLength() > packet->getDataReadLength())
  {
    ArNetPacket sendPacket;  
    // find out the sensor they want
    packet->bufToStr(sensor, sizeof(sensor));
    myRobot->lock();
    if ((dev = myRobot->findRangeDevice(sensor)) == NULL)
    {
      myRobot->unlock();
      ArLog::log(ArLog::Verbose, "ArServerInfoSensor::getSensorCumulative: No sensor %s", sensor);
      sendPacket.byte2ToBuf(-1);
      sendPacket.strToBuf(sensor);
      client->sendPacketUdp(&sendPacket);
      continue;
    }
    
    myRobot->unlock();
    dev->lockDevice();
    readings = dev->getCumulativeBuffer();
    if (readings == NULL)
    {
      dev->unlockDevice();
      ArLog::log(ArLog::Verbose, "ArServerInfoSensor::getSensorCumulative: No current buffer for %s", sensor);
      sendPacket.byte2ToBuf(0);
      sendPacket.strToBuf(sensor);
      client->sendPacketUdp(&sendPacket);
      continue;
    } 
    
    sendPacket.byte2ToBuf(readings->size());
    sendPacket.strToBuf(sensor);
    for (it = readings->begin(); it != readings->end(); it++)
    {
      sendPacket.byte4ToBuf(ArMath::roundInt((*it)->getX()));
      sendPacket.byte4ToBuf(ArMath::roundInt((*it)->getY()));
    }
    dev->unlockDevice();
    client->sendPacketUdp(&sendPacket);
  }

}
void exampleXDrawingNetCallback(ArServerClient* client, ArNetPacket* requestPkt) {
  ArNetPacket reply;

  // X marks the spot. 2 line segments, so 4 vertices:
  reply.byte4ToBuf(4);

  // Segment 1:
  reply.byte4ToBuf(-4250); // X1
  reply.byte4ToBuf(250);   // Y1
  reply.byte4ToBuf(-3750); // X2
  reply.byte4ToBuf(-250);  // Y2

  // Segment 2:
  reply.byte4ToBuf(-4250); // X1
  reply.byte4ToBuf(-250);  // Y1
  reply.byte4ToBuf(-3750); // X2
  reply.byte4ToBuf(250);   // Y2
  
  client->sendPacketUdp(&reply);
}
AREXPORT void ArServerInfoRobot::update(ArServerClient *client, 
					ArNetPacket *packet)
{
  ArNetPacket sending;

  myRobot->lock();

  ArServerMode *netMode;
  if ((netMode = ArServerMode::getActiveMode()) != NULL)
  {
    sending.strToBuf(netMode->getStatus());
    sending.strToBuf(netMode->getMode());
  }
  else 
  {
    sending.strToBuf("Unknown status");
    sending.strToBuf("Unknown mode");
  }


	//ArLog::log(ArLog::Normal,
  //                     "ArServerInfoRobot::update() havestateofcharge = %d, soc = %f, real = %f, reg = %f",
	//											myRobot->haveStateOfCharge(),
	//											myRobot->getStateOfCharge(),
	//											myRobot->getRealBatteryVoltage(),
	//											myRobot->getBatteryVoltage());

  if (myRobot->haveStateOfCharge())
    sending.byte2ToBuf(ArMath::roundInt(myRobot->getStateOfCharge() * 10));
  else if (myRobot->getRealBatteryVoltage() > 0)
    sending.byte2ToBuf(ArMath::roundInt(
	    myRobot->getRealBatteryVoltage() * 10));
  else
    sending.byte2ToBuf(ArMath::roundInt(
	    myRobot->getBatteryVoltage() * 10));

  sending.byte4ToBuf((int)myRobot->getX());
  sending.byte4ToBuf((int)myRobot->getY());
  sending.byte2ToBuf((int)myRobot->getTh());
  sending.byte2ToBuf((int)myRobot->getVel());
  sending.byte2ToBuf((int)myRobot->getRotVel());
  sending.byte2ToBuf((int)myRobot->getLatVel());
  sending.byteToBuf((char)myRobot->getTemperature());
	//sending.byte2ToBuf((int)myRobot->getPayloadNumSlots());
  myRobot->unlock();

  client->sendPacketUdp(&sending);
}
AREXPORT void ArServerInfoRobot::activityTimeInfo(
	ArServerClient *client, 
	ArNetPacket *packet)
{
  ArNetPacket sending;

  // TODO Not entirely sure whether the robot needs to be locked here, but
  // it seems like it shouldn't hurt.
  //
  myRobot->lock();
  sending.byte4ToBuf(ArServerMode::getActiveModeActivityTimeSecSince());
  myRobot->unlock();
  
  client->sendPacketTcp(&sending);

} // end method activityTimeInfo
Beispiel #6
0
AREXPORT void ArServerHandlerPopup::serverCycleCallback(void)
{
  std::map<ArTypes::Byte4, PopupData *>::iterator it;
  ArNetPacket sendingPacket;
  PopupData *popupData;
  int timeout;

  std::list<ArTypes::Byte4> doneIDs;
  std::list<PopupData *> donePopups;
  myDataMutex.lock();
  // only check it if we haven't checked it lately
  if (myLastTimeCheck.mSecSince() > 1000)
  {
    myLastTimeCheck.setToNow();
    for (it = myMap.begin(); it != myMap.end(); it++)
    {
      popupData = (*it).second;
      if ((timeout = popupData->myPopupInfo->getTimeout()) > 0 && 
	  popupData->myStarted.secSince() >= timeout)
      {
	sendingPacket.empty();
	sendingPacket.byte4ToBuf((*it).first);
	sendingPacket.strToBuf(popupData->myPopupInfo->getTimeoutString()); 
	myServer->broadcastPacketTcp(&sendingPacket, "popupClose");
	doneIDs.push_back((*it).first);
	donePopups.push_back(popupData);

      }
    }
  }
  while (doneIDs.begin() != doneIDs.end())
  {
    myMap.erase((*doneIDs.begin()));
    doneIDs.pop_front();
  } 
  myDataMutex.unlock();

  std::list<PopupData *>::iterator donePopupIt;
  while ((donePopupIt = donePopups.begin()) != donePopups.end())
  {
    popupData = (*donePopupIt);
    if (popupData->myCallback != NULL)
      popupData->myCallback->invoke(popupData->myID, -1);
    delete popupData;
    donePopups.pop_front();
  } 
}
int main(int argc, char **argv)
{
  Aria::init();
  //ArLog::init(ArLog::StdOut, ArLog::Verbose);
  ArClientBase client;

  ArArgumentParser parser(&argc, argv);

  ArClientSimpleConnector clientConnector(&parser);
  parser.loadDefaultArguments();

  if (!clientConnector.parseArgs() || !parser.checkHelpAndWarnUnparsed())
  {
    clientConnector.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);
  } 
  client.runAsync();

  ArNetPacket sending;
  // We have to tell it what route we want to patrol
  sending.strToBuf("hallways");
  // tell it how much many times we want to patrol (<= 0 == forever)
  sending.byte4ToBuf(0);

  client.requestOnce("patrolRouteCount", &sending);

  // note that there's also another call (patrol) that just has it always
  // patrol forever but this gives you more options and is only
  // slightly more complicated (just give it that byte4)

  // you have to give the client some time to send the command
  ArUtil::sleep(500);
  

  Aria::shutdown();
  return 0;
}
Beispiel #8
0
AREXPORT void ArServerHandlerPopup::netPopupClicked(ArServerClient *client,
						     ArNetPacket *packet)
{
  ArNetPacket sendingPacket;
  PopupData *popupData;
  std::map<ArTypes::Byte4, PopupData *>::iterator it;

  ArTypes::Byte4 id;
  ArTypes::Byte button;

  id = packet->bufToByte4();
  button = packet->bufToByte();

  myDataMutex.lock();
  if ((it = myMap.find(id)) == myMap.end())
  {
    ArLog::log(ArLog::Verbose, 
       "Cannot close popup %u for client %s as it doesn't exist (anymore at least)", 
	       id, client->getIPString());
    myDataMutex.unlock();
  }
  else
  {
    popupData = (*it).second;
    sendingPacket.byte4ToBuf(id);
    if (button == 0)
      sendingPacket.strToBuf(popupData->myPopupInfo->getButton0Pressed()); 
    else if (button == 1)
      sendingPacket.strToBuf(popupData->myPopupInfo->getButton1Pressed()); 
    else if (button == 2)
      sendingPacket.strToBuf(popupData->myPopupInfo->getButton2Pressed()); 
    else 
      sendingPacket.strToBuf("Popup closed because of odd click");
    myMap.erase(id);
    myDataMutex.unlock();
    if (popupData->myCallback != NULL)
      popupData->myCallback->invoke(popupData->myID, button);
    delete popupData;
    myServer->broadcastPacketTcp(&sendingPacket, "popupClose");
  }

  
}
void exampleDotsDrawingNetCallback(ArServerClient* client, ArNetPacket* requestPkt) {
  ArNetPacket reply;

  unsigned int tik = ArUtil::getTime() % 200;
  double t = tik / 5.0;

  // Three dots
  reply.byte4ToBuf(3);

  // Dot 1:
  reply.byte4ToBuf(3000);  // X coordinate (mm)
  reply.byte4ToBuf((int) (sin(t) * 1000));// Y

  // Dot 2:
  reply.byte4ToBuf(3500);  // X
  reply.byte4ToBuf((int) (sin(t+500) * 1000));// Y

  // Dot 3:
  reply.byte4ToBuf(4000);  // X
  reply.byte4ToBuf((int) (sin(t+1000) * 1000));// Y

  client->sendPacketUdp(&reply);
}
void exampleHomeDrawingNetCallback(ArServerClient* client, ArNetPacket* requestPkt) {
  ArNetPacket reply;

  // 7 Vertices
  reply.byte4ToBuf(7);

  // Centered on 0,0.
  // X:                    Y:
  reply.byte4ToBuf(-500);  reply.byte4ToBuf(500);   // Vertex 1
  reply.byte4ToBuf(-500);  reply.byte4ToBuf(-500);  // Vertex 2
  reply.byte4ToBuf(500);   reply.byte4ToBuf(-500);  // Vertex 3
  reply.byte4ToBuf(500);   reply.byte4ToBuf(500);   // Vertex 4
  reply.byte4ToBuf(0);     reply.byte4ToBuf(1000);  // Vertex 5
  reply.byte4ToBuf(-500);  reply.byte4ToBuf(500);   // Vertex 6
  reply.byte4ToBuf(500);   reply.byte4ToBuf(500);   // Vertex 7

  client->sendPacketUdp(&reply);
}
AREXPORT void ArServerHandlerMap::sendMapWithMaxCategory(ArServerClient *client,
				                                                 const char *maxCategory)
{
  ArLog::LogLevel level = ArLog::Verbose;

  ArLog::log(level, 
             "Starting sending map (%s) to client", maxCategory);

  if (myMap == NULL)
  {
    ArLog::log(level, 
               "ArServerHandlerMap::sendMapWithMaxCategory() NULL map");

    writeMapToClient("", client);
    return;
  }

  myMap->lock();
  // This functor is used to send the map header and objects in text format.
  ArFunctor1<const char *> *textFunctor = 
		new ArFunctor2C<ArServerHandlerMap, const char *, ArServerClient *>
					(this, 
					 &ArServerHandlerMap::writeMapToClient,
					 NULL,
					 client);

  // This functor is used to send the map data lines in binary format (since
  // it is faster).
  ArFunctor2<int, std::vector<ArLineSegment> *> *linesFunctor =
	  new ArFunctor3C<ArServerHandlerMap, int, std::vector<ArLineSegment> *, ArServerClient *>
				   (this,
				    &ArServerHandlerMap::writeLinesToClient,
				    0,
				    NULL,
				    client);

  // This functor is used to send the map data points in binary format (since
  // it is faster).
  ArFunctor2<int, std::vector<ArPose> *> *pointsFunctor =
	  new ArFunctor3C<ArServerHandlerMap, int, std::vector<ArPose> *, ArServerClient *>
				   (this,
				    &ArServerHandlerMap::writePointsToClient,
				    0,
				    NULL,
				    client);

  // Send the map up to but not including the DATA tag.
  myMap->writeObjectsToFunctor(textFunctor, 
                               "", 
                               false,
                               maxCategory);

  std::list<std::string> scanTypeList = myMap->getScanTypes();

  if (!scanTypeList.empty()) {

    // see if we want to send the lines and make sure we have lines
    if (myDataToSend == LINES || myDataToSend == BOTH) {
    
      for (std::list<std::string>::iterator iter = scanTypeList.begin();
           iter != scanTypeList.end();
           iter++) {
        const char *scanType = (*iter).c_str();
        if ((myMap->getLines(scanType) != NULL) &&
            (!myMap->getLines(scanType)->empty())) {

          myMap->writeLinesToFunctor(linesFunctor,
                                     scanType,
                                     textFunctor);
          ArNetPacket sendPacket;
          sendPacket.empty();
          sendPacket.byte4ToBuf(0);
          client->sendPacketTcp(&sendPacket);
        }
      }
    }
    if (myDataToSend == POINTS || myDataToSend == BOTH) {
 
      // TODO This is different than getMapBinary -- in that DATA is not necessarily
      // always sent.  Is this going to be a problem?

      for (std::list<std::string>::iterator iter = scanTypeList.begin();
           iter != scanTypeList.end();
           iter++) {
        const char *scanType = (*iter).c_str();
        if ((myMap->getPoints(scanType) != NULL) &&
            (!myMap->getPoints(scanType)->empty())) {

          myMap->writePointsToFunctor(pointsFunctor,
                                      scanType,
                                      textFunctor);
          ArNetPacket sendPacket;
          sendPacket.empty();
          sendPacket.byte4ToBuf(0);
          client->sendPacketTcp(&sendPacket);
        }
      }
    }
  } // end if scan types
  
  // send an empty packet to say we're done
  ArNetPacket emptyPacket;
  client->sendPacketTcp(&emptyPacket);

  myMap->unlock();
  ArLog::log(level, "Finished sending map (%s) to client", maxCategory);
  
  // delete textFunctor;
  
  delete textFunctor;
  textFunctor = NULL;
  delete linesFunctor;
  linesFunctor = NULL;
  delete pointsFunctor;
  pointsFunctor = NULL;

} // end method sendMapWithMaxCategory
AREXPORT void ArServerHandlerMap::serverGetMapBinary(ArServerClient *client, 
													                           ArNetPacket *packet)
{
  ArLog::log(ArLog::Verbose, "Starting sending map (binary) to client");
  if (myMap == NULL)
  {
    writeMapToClient("", client);
    return;
  }

  myMap->lock();
  // This functor is used to send the map header and objects in text format.
  ArFunctor1<const char *> *textFunctor = 
		new ArFunctor2C<ArServerHandlerMap, const char *, ArServerClient *>
					(this, 
					 &ArServerHandlerMap::writeMapToClient,
					 NULL,
					 client);

  // This functor is used to send the map data lines in binary format (since
  // it is faster).
  ArFunctor2<int, std::vector<ArLineSegment> *> *linesFunctor =
	  new ArFunctor3C<ArServerHandlerMap, int, std::vector<ArLineSegment> *, ArServerClient *>
				   (this,
				    &ArServerHandlerMap::writeLinesToClient,
				    0,
				    NULL,
				    client);

  // This functor is used to send the map data points in binary format (since
  // it is faster).
  ArFunctor2<int, std::vector<ArPose> *> *pointsFunctor =
	  new ArFunctor3C<ArServerHandlerMap, int, std::vector<ArPose> *, ArServerClient *>
				   (this,
				    &ArServerHandlerMap::writePointsToClient,
				    0,
				    NULL,
				    client);

  // Send the map up to but not including the DATA tag.
  myMap->writeObjectsToFunctor(textFunctor, 
                               "", 
                               true, // Only send one scan type
                               ArMapInterface::MAP_CATEGORY_2D);

  std::list<std::string> scanTypeList = myMap->getScanTypes();

  bool isAnyLinesExist = false;
  
  for (std::list<std::string>::iterator iter = scanTypeList.begin();
        iter != scanTypeList.end();
        iter++) {
    const char *scanType = (*iter).c_str();
    if ((myMap->getLines(scanType) != NULL) &&
        (!myMap->getLines(scanType)->empty())) {
      isAnyLinesExist = true;
      break;
    } 
  } // end for each scan type

  // see if we want to send the lines and make sure we have lines
  if ((myDataToSend == LINES || myDataToSend == BOTH) && 
      isAnyLinesExist) 
  {
    writeMapToClient("LINES", client);

    /***
    myMap->writeLinesToFunctor(linesFunctor, 
                               NULL, 
                               ARMAP_SUMMARY_SCAN_TYPE);
   
    ***/
    for (std::list<std::string>::iterator iter = scanTypeList.begin();
         iter != scanTypeList.end();
         iter++) {
      const char *scanType = (*iter).c_str();
      ArLog::log(ArLog::Normal,
                 "ArServerHandlerMap::serverGetMapBinary() sending lines for %s",
                 scanType);

      myMap->writeLinesToFunctor(linesFunctor, scanType, NULL);
    
    } // end for each scan type

    ArNetPacket sendPacket;
    sendPacket.empty();
    sendPacket.byte4ToBuf(0);
    client->sendPacketTcp(&sendPacket);

    /****/
  }

  // Always write the points (even if empty) because this signifies
  // the end of the map for the client.
  //if (myMap->getPoints()->begin() != myMap->getPoints()->end())
  //{
  writeMapToClient("DATA", client);
  // if we want to send points then send 'em
  if (myDataToSend == POINTS || myDataToSend == BOTH) 
  {
    // myMap->writePointsToFunctor(pointsFunctor, NULL, sendScanType);
    /**/
    for (std::list<std::string>::iterator iter = scanTypeList.begin();
         iter != scanTypeList.end();
         iter++) {
      const char *scanType = (*iter).c_str();
      ArLog::log(ArLog::Normal,
                 "ArServerHandlerMap::serverGetMapBinary() sending points for %s",
                 scanType);
      myMap->writePointsToFunctor(pointsFunctor, scanType, NULL);
    } // end for each scan type
    /**/
    ArNetPacket sendPacket;
    sendPacket.empty();
    sendPacket.byte4ToBuf(0);
    client->sendPacketTcp(&sendPacket);
  }
  // if not just say we're done
  else
    writeMapToClient("", client);
  //}

  // send an empty packet to say we're done
  ArNetPacket emptyPacket;
  client->sendPacketTcp(&emptyPacket);

  myMap->unlock();
  ArLog::log(ArLog::Verbose, "Finished sending map (binary) to client");
  
  // delete textFunctor;
  
  delete textFunctor;
  textFunctor = NULL;
  delete linesFunctor;
  linesFunctor = NULL;
  delete pointsFunctor;
  pointsFunctor = NULL;

}
/** @internal */
AREXPORT void ArServerHandlerMap::writeLinesToClient(
	int lineCount,
	std::vector<ArLineSegment> *lines,
	ArServerClient *client)
{
  ArNetPacket sendPacket;
  
  // Should never happen...
  if (lines == NULL) {
    // Send 0 points just so the client doesn't hang
    sendPacket.byte4ToBuf(0);
    client->sendPacketTcp(&sendPacket);
    return;
  }
  
  ArLog::log(ArLog::Verbose, 
	     "ArServerHandlerMap::writeLinesToClient() pointCount = %i, vector size = %i", 
	     lineCount, (int) lines->size());
  
  // Neither should this, but just in case...
  if (lineCount > (int) lines->size()) {
    lineCount = lines->size();
  }
  
  int maxInPacketCount = 1000; // Maximum number of points sent in a packet
  int currentCount = 0;		// Number put into the current packet 
  int remainingCount = lineCount; // Total number of points remaining to be sent
  bool isStartPacket = true;	// Whether a new packet is being started
  
  int totalCount = 0;
  
  for (std::vector<ArLineSegment>::iterator lineIt = lines->begin(); 
       lineIt != lines->end();
       lineIt++) 
  {
    
    // Start a new packet if the previous one was sent (or there is no 
    // previous one)
    if (isStartPacket) {
      
      isStartPacket = false;
      
      sendPacket.empty();
      currentCount = 0;
      
      // Leftover points...
      if (maxInPacketCount > remainingCount) {
	maxInPacketCount = remainingCount;
      }
      
      // The first item in the packet is the number of points contained
      sendPacket.byte4ToBuf(maxInPacketCount);
      
    } // end if starting a new packet
    
    // Add the current point to the packet (think that the test should 
    // always be true)
    if (currentCount < maxInPacketCount) {
      
      currentCount++;
      remainingCount--;
      
      sendPacket.byte4ToBuf(
	      ArMath::roundInt((*lineIt).getX1()));
      sendPacket.byte4ToBuf(
	      ArMath::roundInt((*lineIt).getY1()));
      sendPacket.byte4ToBuf(
	      ArMath::roundInt((*lineIt).getX2()));
      sendPacket.byte4ToBuf(
	      ArMath::roundInt((*lineIt).getY2()));
    }
    
    // If the packet is full, send it and then start a new one
    if (currentCount == maxInPacketCount) {
      
      totalCount += currentCount;
      
      client->sendPacketTcp(&sendPacket);
      //ArUtil::sleep(1);
      
      isStartPacket = true;
    }
    
  } // end for each point
  
  ArLog::log(ArLog::Verbose, 
	     "ArServerHandlerMap::writePointsToClient() totalCount = %i", 
	     totalCount);
  
  // Send 0 points to indicate that all have been sent
  if (false) {
  sendPacket.empty();
  sendPacket.byte4ToBuf(0);
  client->sendPacketTcp(&sendPacket);
  }

} // end writePointsToClient
AREXPORT void ArServerClient::processPacket(ArNetPacket *packet, bool tcp)
{
  std::string str;
  struct sockaddr_in sin;
  unsigned int clientUdpPort;
  ArNetPacket retPacket;

  //printf("Command number %d\n", packet->getCommand());
  // if we're in intro mode and received back the intro
  if (myState == STATE_SENT_INTRO && 
      packet->getCommand() == ArClientCommands::INTRODUCTION)
  {
    char user[512];
    unsigned char password[16];
    clientUdpPort = packet->bufToUByte2();
    packet->bufToStr(user, sizeof(user));
    packet->bufToData((char *)password, 16);

    if (myRejecting != 0)
    {
      retPacket.empty();
      retPacket.setCommand(ArServerCommands::REJECTED);
      retPacket.byte2ToBuf(myRejecting);
      retPacket.strToBuf(myRejectingString.c_str());
      sendPacketTcp(&retPacket);
      if (myRejecting == 2)
	ArLog::log(ArLog::Normal, 
   "%sRejected connection from %s since we're using a central server at %s",
		   myLogPrefix.c_str(), getIPString(), 
		   myRejectingString.c_str());
      internalSwitchState(STATE_REJECTED);
      return;
    }

    // if user info is NULL we're not checking passwords
    if (myUserInfo != NULL && 
	!myUserInfo->matchUserPassword(user, password, myPasswordKey.c_str(),
				       myServerKey.c_str(),
				       myLogPasswordFailureVerbosely))
    {
      retPacket.empty();
      retPacket.setCommand(ArServerCommands::REJECTED);
      retPacket.byte2ToBuf(1);
      retPacket.strToBuf("");
      sendPacketTcp(&retPacket);
      ArLog::log(ArLog::Normal, "%sRejected user '%s' or password from %s",
		 myLogPrefix.c_str(), user, getIPString());
      internalSwitchState(STATE_REJECTED);
      return;
    }
    if (myUserInfo != NULL)
      myGroups = myUserInfo->getUsersGroups(user);
    else
      myGroups.clear();
    sin.sin_family = AF_INET;
    sin.sin_addr = *myTcpSocket.inAddr();
    sin.sin_port = ArSocket::hostToNetOrder(clientUdpPort);
    if (myUserInfo != NULL)
      ArLog::log(ArLog::Normal, 
		 "%sClient connected from %s with user %s", 
		 myLogPrefix.c_str(), getIPString(), user);
    else
      ArLog::log(ArLog::Normal, 
		 "%sClient connected from %s", myLogPrefix.c_str(), 
		 getIPString());

    setUdpAddress(&sin);
    // send that we've connected
    retPacket.empty();
    retPacket.setCommand(ArServerCommands::CONNECTED);
    sendPacketTcp(&retPacket);
    // note that we're connected
    internalSwitchState(STATE_CONNECTED);

    // send them the list
    sendListPacket();
    // send the udp introduction if we're using udp
    if (!myTcpOnly)
    {
      retPacket.empty();
      retPacket.setCommand(ArServerCommands::UDP_INTRODUCTION);
      retPacket.byte4ToBuf(myIntroKey);
      sendPacketUdp(&retPacket);
    }
  }
  // if we aren't in intro mode and got an intro somethings wrong
  else if (packet->getCommand() == ArClientCommands::INTRODUCTION)
  {
    ArLog::log(ArLog::Terse, 
	       "%sReceived introduction when not in intro mode",
	       myLogPrefix.c_str());
    return;
  }
  // if we got this over tcp then they only want tcp
  else if (packet->getCommand() == ArClientCommands::UDP_INTRODUCTION)
  {
    if (!myTcpOnly)
    {
      ArLog::log(ArLog::Normal, "%sGot UDP introduction over tcp, assuming client only wants tcp data.", myLogPrefix.c_str());
      myTcpOnly = true;
    }
    return;
  }
  // if we're connected and got a udp confirmation
  else if ((myState == STATE_CONNECTED || 
	    myState == STATE_SENT_INTRO) && 
	   packet->getCommand() == ArClientCommands::UDP_CONFIRMATION)
  {
    myUdpConfirmedTo = true;
    ArLog::log(myVerboseLogLevel, 
	       "%s: udp connection to client confirmed.", myLogPrefix.c_str());
    return;
  }
  // if we're not connected (or close) and got a confirmation
  else if (packet->getCommand() == ArClientCommands::UDP_CONFIRMATION)
  {
    ArLog::log(ArLog::Normal, 
	       "%sReceived udp confirmation when not connected.",
	       myLogPrefix.c_str());
    return;
  }
  else if (packet->getCommand() == ArClientCommands::TCP_ONLY)
  {
    ArLog::log(myVerboseLogLevel, "%sClient only wants tcp data.", myLogPrefix.c_str());
    myTcpOnly = true;
    return;
  }
  else if (packet->getCommand() == ArClientCommands::SHUTDOWN)
  {
    ArLog::log(ArLog::Normal, "%sClient from %s has disconnected.",
	       myLogPrefix.c_str(), getIPString());
    internalSwitchState(STATE_DISCONNECTED);
    return;
  }
  // if we're connected its a request, then set all that up
  else if (myState == STATE_CONNECTED && 
	   packet->getCommand() == ArClientCommands::REQUEST)
  {
    std::list<ArServerClientData *>::iterator it;
    ArServerClientData *data;
    ArServerData *serverData;
    unsigned int command;
    long mSec;
    // see which one they requested
    command = packet->bufToUByte2();
    mSec = packet->bufToByte4();

    // first we see if we already have this one
    for (it = myRequested.begin(); it != myRequested.end(); ++it)
    {
      data = (*it);
      serverData = data->getServerData();
      if (serverData->getCommand() == command)
      {
	trackPacketReceived(packet, command);
	data->setMSec(mSec);
	data->setPacket(packet);
	data->getPacket()->setCommand(command);
	serverData->callRequestChangedFunctor();
	ArLog::log(myVerboseLogLevel, 
	   "%sRevised request for command %s to %d mSec with new argument", 
		   myLogPrefix.c_str(), 
		   findCommandName(serverData->getCommand()), mSec);
	return;
      }
    }
    // we didn't have it, so make a new one
    std::map<unsigned int, ArServerData *>::iterator sdit;
    if ((sdit = myDataMap->find(command)) == myDataMap->end())
    {
      ArLog::log(ArLog::Terse, 
  	      "%sGot request for command %d which doesn't exist", 
		 myLogPrefix.c_str(), command);
      return;
    }
    serverData = (*sdit).second;
    if (serverData == NULL) 
    {
      ArLog::log(ArLog::Terse, 
		 "%sprocessPackets request handler has NULL serverData", 
		 myLogPrefix.c_str());
    }
    if (myUserInfo != NULL && 
	serverData->getCommandGroup() != NULL &&
	serverData->getCommandGroup()[0] != '\0' &&
	myGroups.count(serverData->getCommandGroup()) == 0 &&
	myGroups.count("all") == 0)
    {
      ArLog::log(ArLog::Normal, 
		 "%s%s tried to request command '%s' but it doesn't have access to that command", 
		 myLogPrefix.c_str(), getIPString(), 
		 serverData->getName());
      return;
    }
    trackPacketReceived(packet, command);
    data = new ArServerClientData(serverData, mSec, packet);
    data->getPacket()->setCommand(command);
    ArLog::log(myVerboseLogLevel, 
	       "%sadded request for command %s every %d mSec", 
	       myLogPrefix.c_str(), serverData->getName(), mSec);
    if (mSec == 0)
      ArLog::log(ArLog::Normal, "%sClient from %s requested command %s every at 0 msec", myLogPrefix.c_str(), 
		 getIPString(), serverData->getName());
    myRequested.push_front(data);
    serverData->callRequestChangedFunctor();
    pushCommand(command);
    pushForceTcpFlag(false);
    if (serverData->getFunctor() != NULL)
      serverData->getFunctor()->invoke(this, data->getPacket());
    popCommand();
    popForceTcpFlag();
    return;
  }
  // if we got a request when we're not connected
  else if (packet->getCommand() == ArClientCommands::REQUEST)
  {
    ArLog::log(ArLog::Normal, 
	       "Got a request while not connected.",
	       myLogPrefix.c_str());
    return;
  }
  // if we're connected its a requestStop, then set all that up
  else if (myState == STATE_CONNECTED && 
	   packet->getCommand() == ArClientCommands::REQUESTSTOP)
  {
    std::list<ArServerClientData *>::iterator it;
    ArServerClientData *data;
    ArServerData *serverData;
    unsigned int command;
    // see which one they requested
    command = packet->bufToUByte2();

    // first we see if we have this one
    for (it = myRequested.begin(); it != myRequested.end(); ++it)
    {
      data = (*it);
      serverData = data->getServerData();
      // we have a match, so set the new params then return
      if (data->getServerData()->getCommand() == command)
      {
	trackPacketReceived(packet, command);
	myRequested.erase(it);
	ArLog::log(myVerboseLogLevel, "%sStopped request for command %s", 
		   myLogPrefix.c_str(), 
		   findCommandName(serverData->getCommand()));
	delete data;
	serverData->callRequestChangedFunctor();
	return;
      }
    }
    // if we don't have it... that means that it wasn't here
    
    // find out what to call it
    std::map<unsigned int, ArServerData *>::iterator sdit;
    if ((sdit = myDataMap->find(command)) == myDataMap->end())
    {
      ArLog::log(ArLog::Terse, 
		 "%sGot a requeststop for command %d which doesn't exist", 
		 myLogPrefix.c_str(), command);
      return;
    }
    trackPacketReceived(packet, command);
    serverData = (*sdit).second;
    if (serverData == NULL) 
      ArLog::log(ArLog::Terse, 
		 "%srequeststop handler has NULL serverData on back command %d", 
		 myLogPrefix.c_str(), command);
    else
      ArLog::log(ArLog::Normal, "%s: Got a stop request for command %s that isn't requested", myLogPrefix.c_str(), serverData->getName());
    return;
  }
  // if we got a requestStop when we're not connected
  else if (packet->getCommand() == ArClientCommands::REQUESTSTOP)
  {
    ArLog::log(ArLog::Normal, 
	       "%sGot a requeststop while not connected.", 
	       myLogPrefix.c_str());
    return;
  }
  // if we're connected and its a command to execute just once
  else if (myState == STATE_CONNECTED)
  {
    unsigned int command;
    std::map<unsigned int, ArServerData *>::iterator it;
    ArServerData *serverData;

    command = packet->getCommand();
    if ((it = myDataMap->find(command)) == myDataMap->end())
    {
      ArLog::log(ArLog::Terse, 
  	      "%sArServerClient got request for command %d which doesn't exist", 
		 myLogPrefix.c_str(), command);
      return;
    }
    serverData = (*it).second;
    if (myUserInfo != NULL && 
	serverData->getCommandGroup() != NULL &&
	serverData->getCommandGroup()[0] != '\0' &&
	myGroups.count(serverData->getCommandGroup()) == 0 &&
	myGroups.count("all") == 0)
    {
      ArLog::log(ArLog::Normal, 
		 "%s%s tried to request command '%s' once but it doesn't have access to that command", myLogPrefix.c_str(),
		 getIPString(), 
		 serverData->getName());
      return;
    }
    trackPacketReceived(packet, command);

    // copy it out and return if its an idle packet
    if (myAllowIdlePackets && serverData->isIdlePacket())
    {
      myHaveIdlePackets = true;
      if (command <= 255)
	ArLog::log(myVerboseLogLevel, "%sStoring idle command %d", 
		   myLogPrefix.c_str(), command);
      else
	ArLog::log(myVerboseLogLevel, "%sStoring idle command %s", 
		   myLogPrefix.c_str(), serverData->getName());
      myIdlePacketsMutex.lock();
      ArNetPacket *idlePacket = new ArNetPacket(packet->getLength() + 5);
      idlePacket->duplicatePacket(packet);
      myIdlePackets.push_back(idlePacket);
      myIdlePacketsMutex.unlock();
      return;
    }
    // If its a slow or an idle packet (and we're not allowing the
    // idle behavior) and we allow slow packets then copy it
    else if (myAllowSlowPackets && (serverData->isSlowPacket() || 
				    serverData->isIdlePacket()))
    {
      myHaveSlowPackets = true;
      if (command <= 255)
	ArLog::log(myVerboseLogLevel, "%sStoring slow command %d", 
		   myLogPrefix.c_str(), command);
      else
	ArLog::log(myVerboseLogLevel, "%sStoring slow command %s", 
		   myLogPrefix.c_str(), serverData->getName());
      mySlowPacketsMutex.lock();
      ArNetPacket *slowPacket = new ArNetPacket(packet->getLength() + 5);
      slowPacket->duplicatePacket(packet);
      mySlowPackets.push_back(slowPacket);
      mySlowPacketsMutex.unlock();
      return;
    }


    if (command <= 255)
      ArLog::log(myVerboseLogLevel, "%sGot command %s", 
		 myLogPrefix.c_str(), serverData->getName());
    else
      ArLog::log(ArLog::Verbose, "%sGot command %s", 
		 myLogPrefix.c_str(), serverData->getName());
    pushCommand(command);
    pushForceTcpFlag(tcp);
    if (serverData->getFunctor() != NULL)
      serverData->getFunctor()->invoke(this, packet);
    if (serverData->getRequestOnceFunctor() != NULL)
      serverData->getRequestOnceFunctor()->invoke(this, packet);
    popCommand();
    popForceTcpFlag();
    return;
  }
  else
  {
    ArLog::log(ArLog::Terse, 
	       "%sRogue packet command %s in state %d", myLogPrefix.c_str(),
	       findCommandName(packet->getCommand()), myState);
  }
}
AREXPORT void ArServerHandlerCameraCollection::getCameraList(ArServerClient *client,
        ArNetPacket *packet)
{
    if (client == NULL) {
        return; // Something very bad has happened...
    }

    ArNetPacket sendPacket;

    if (myCameraCollection == NULL) {
        sendPacket.byte2ToBuf(0);
        client->sendPacketTcp(&sendPacket);
    }

    // This lack of recursive locks is troublesome... Data might
    // change between calls...

    std::list<std::string> cameraNames;
    myCameraCollection->getCameraNames(cameraNames);

    sendPacket.byte2ToBuf(cameraNames.size());

    for (std::list<std::string>::iterator iter = cameraNames.begin();
            iter != cameraNames.end();
            iter++) {

        const char *curName = iter->c_str();

        sendPacket.strToBuf(curName);

        // TODO: ArNetPacket will NOT behave correctly if the given str is NULL
        // Fix this somehow...

        sendPacket.strToBuf(myCameraCollection->getCameraType(curName));
        sendPacket.strToBuf(myCameraCollection->getDisplayName(curName));
        sendPacket.strToBuf(myCameraCollection->getDisplayType(curName));

        // Send commands...

        std::list<std::string> commands;
        myCameraCollection->getCameraCommands(curName, commands);

        sendPacket.byte2ToBuf(commands.size());

        for (std::list<std::string>::iterator comIter = commands.begin();
                comIter != commands.end();
                comIter++) {

            const char *curCommand = comIter->c_str();

            sendPacket.strToBuf(curCommand);
            sendPacket.strToBuf(myCameraCollection->getCommandName(curName, curCommand));
            sendPacket.byte4ToBuf(myCameraCollection->getRequestInterval(curName, curCommand));

        } // end for each command

        // Send parameters...

        std::list<std::string> params;
        myCameraCollection->getParameterNames(curName, params);

        sendPacket.byte2ToBuf(params.size());

        ArConfigArg arg;
        ArClientArg clientArg;

        bool isSuccess = true;

        for (std::list<std::string>::iterator paramIter = params.begin();
                paramIter != params.end();
                paramIter++) {

            const char *paramName = paramIter->c_str();

            isSuccess = myCameraCollection->getParameter(curName,
                        paramName,
                        arg);
            if (!isSuccess) {
                ArLog::log(ArLog::Normal,
                           "ArServerHandlerCameraCollection::getCameraList() could not find param %s", paramName);
                continue;
            }

            // Add the current parameter to the packet
            isSuccess = clientArg.createPacket(arg, &sendPacket);

        } // end for each parameter

    } // end for each camera

    client->sendPacketTcp(&sendPacket);

} // end method getCameraList