Update of /cvsroot/playerstage/code/player/server/drivers/mixed/p2os
In directory 
sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv30199/server/drivers/mixed/p2os

Modified Files:
        p2os.cc sip.cc 
Log Message:
overhaul of the player interface definitions
interfaces are now defined with a very light weight IDL allowing them to be 
edited in a single file
some subtype names were also modified as a side effect, making them more 
consistent globally


Index: sip.cc
===================================================================
RCS file: /cvsroot/playerstage/code/player/server/drivers/mixed/p2os/sip.cc,v
retrieving revision 1.23
retrieving revision 1.24
diff -C2 -d -r1.23 -r1.24
*** sip.cc      31 Jan 2007 21:20:30 -0000      1.23
--- sip.cc      20 Aug 2007 06:37:29 -0000      1.24
***************
*** 152,156 ****
    // digital I/O
    data->dio.count = (unsigned char)8;
!   data->dio.digin = (unsigned int)this->digin;
  
    ///////////////////////////////////////////////////////////////
--- 152,156 ----
    // digital I/O
    data->dio.count = (unsigned char)8;
!   data->dio.bits = (unsigned int)this->digin;
  
    ///////////////////////////////////////////////////////////////

Index: p2os.cc
===================================================================
RCS file: /cvsroot/playerstage/code/player/server/drivers/mixed/p2os/p2os.cc,v
retrieving revision 1.81
retrieving revision 1.82
diff -C2 -d -r1.81 -r1.82
*** p2os.cc     9 Jul 2007 17:18:01 -0000       1.81
--- p2os.cc     20 Aug 2007 06:37:29 -0000      1.82
***************
*** 119,135 ****
  
  - "odometry" @ref interface_position2d :
!   - PLAYER_POSITION_SET_ODOM_REQ
!   - PLAYER_POSITION_MOTOR_POWER_REQ
!   - PLAYER_POSITION_RESET_ODOM_REQ
!   - PLAYER_POSITION_GET_GEOM_REQ
!   - PLAYER_POSITION_VELOCITY_MODE_REQ
  - @ref interface_sonar :
!   - PLAYER_SONAR_POWER_REQ
!   - PLAYER_SONAR_GET_GEOM_REQ
  - @ref interface_bumper :
!   - PLAYER_BUMPER_GET_GEOM
  - @ref interface_blobfinder :
!   - PLAYER_BLOBFINDER_SET_COLOR_REQ
!   - PLAYER_BLOBFINDER_SET_IMAGER_PARAMS_REQ
  
  @par Configuration file options
--- 119,135 ----
  
  - "odometry" @ref interface_position2d :
!   - PLAYER_POSITION2D_REQ_SET_ODOM
!   - PLAYER_POSITION2D_REQ_MOTOR_POWER
!   - PLAYER_POSITION2D_REQ_RESET_ODOM
!   - PLAYER_POSITION2D_REQ_GET_GEOM
!   - PLAYER_POSITION2D_REQ_VELOCITY_MODE
  - @ref interface_sonar :
!   - PLAYER_SONAR_REQ_POWER
!   - PLAYER_SONAR_REQ_GET_GEOM
  - @ref interface_bumper :
!   - PLAYER_BUMPER_REQ_GET_GEOM
  - @ref interface_blobfinder :
!   - PLAYER_BLOBFINDER_REQ_SET_COLOR
!   - PLAYER_BLOBFINDER_REQ_SET_IMAGER_PARAMS
  
  @par Configuration file options
***************
*** 531,537 ****
      }
      // Stop actarray messages in the queue from being overwritten
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_POS_CMD, false);
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_SPEED_CMD, false);
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_HOME_CMD, false);
    }
  
--- 531,537 ----
      }
      // Stop actarray messages in the queue from being overwritten
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_POS, false);
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_SPEED, false);
!     this->InQueue->AddReplaceRule (this->actarray_id, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_HOME, false);
    }
  
***************
*** 1470,1474 ****
    this->Publish(this->limb_id, NULL,
                  PLAYER_MSGTYPE_DATA,
!                 PLAYER_LIMB_DATA,
                  (void*)&(this->limb_data),
                  sizeof(player_limb_data_t),
--- 1470,1474 ----
    this->Publish(this->limb_id, NULL,
                  PLAYER_MSGTYPE_DATA,
!                 PLAYER_LIMB_DATA_STATE,
                  (void*)&(this->limb_data),
                  sizeof(player_limb_data_t),
***************
*** 2075,2094 ****
    HANDLE_CAPABILITY_REQUEST (position_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_POSITION2D_CMD_VEL);
    // Act array caps
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_POS_CMD);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_MULTI_POS_CMD);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_HOME_CMD);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_POWER_REQ);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_GET_GEOM_REQ);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_SPEED_REQ);
    // Lift caps
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_POS_CMD);
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_HOME_CMD);
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_GET_GEOM_REQ);
    // Limb caps
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_HOME_CMD);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_STOP_CMD);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_SETPOSE_CMD);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_POWER_REQ);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_GEOM_REQ);
    // Gripper caps
    HANDLE_CAPABILITY_REQUEST (gripper_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_GRIPPER_CMD_OPEN);
--- 2075,2094 ----
    HANDLE_CAPABILITY_REQUEST (position_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_POSITION2D_CMD_VEL);
    // Act array caps
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_CMD_POS);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_CMD_MULTI_POS);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_CMD_HOME);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_REQ_POWER);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_REQ_GET_GEOM);
!   HANDLE_CAPABILITY_REQUEST (actarray_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_REQ_SPEED);
    // Lift caps
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_CMD_POS);
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_ACTARRAY_CMD_HOME);
!   HANDLE_CAPABILITY_REQUEST (lift_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_ACTARRAY_REQ_GET_GEOM);
    // Limb caps
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_HOME);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_STOP);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_SETPOSE);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_REQ_POWER);
!   HANDLE_CAPABILITY_REQUEST (limb_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_REQ_GEOM);
    // Gripper caps
    HANDLE_CAPABILITY_REQUEST (gripper_id, resp_queue, hdr, data, 
PLAYER_MSGTYPE_CMD, PLAYER_GRIPPER_CMD_OPEN);
***************
*** 2372,2382 ****
      return(0);
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_POWER_REQ,this->actarray_id))
    {
      ToggleActArrayPower (((player_actarray_power_config_t*) data)->value);
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_POWER_REQ);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_GET_GEOM_REQ,this->actarray_id))
    {
      // First ask for an ARMINFOpac (because we need to get any updates to 
speed settings)
--- 2372,2382 ----
      return(0);
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_REQ_POWER,this->actarray_id))
    {
      ToggleActArrayPower (((player_actarray_power_config_t*) data)->value);
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_REQ_POWER);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_REQ_GET_GEOM,this->actarray_id))
    {
      // First ask for an ARMINFOpac (because we need to get any updates to 
speed settings)
***************
*** 2415,2422 ****
      aaGeom.base_orientation.pyaw = aaBaseOrient.pyaw;
  
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_GET_GEOM_REQ, &aaGeom, sizeof (aaGeom), NULL);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_SPEED_REQ,this->actarray_id))
    {
      joint = ((player_actarray_speed_config_t*) data)->joint + 1;
--- 2415,2422 ----
      aaGeom.base_orientation.pyaw = aaBaseOrient.pyaw;
  
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_REQ_GET_GEOM, &aaGeom, sizeof (aaGeom), NULL);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_REQ_SPEED,this->actarray_id))
    {
      joint = ((player_actarray_speed_config_t*) data)->joint + 1;
***************
*** 2424,2442 ****
      SetActArrayJointSpeed (joint, newSpeed);
  
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_SPEED_REQ);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_POWER_REQ,this->limb_id))
    {
      ToggleActArrayPower (((player_actarray_power_config_t*) data)->value);
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_POWER_REQ);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_BRAKES_REQ,this->limb_id))
    {
      // We don't have any brakes
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_GEOM_REQ,this->limb_id))
    {
      player_limb_geom_req_t limbGeom;
--- 2424,2442 ----
      SetActArrayJointSpeed (joint, newSpeed);
  
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_REQ_SPEED);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_REQ_POWER,this->limb_id))
    {
      ToggleActArrayPower (((player_actarray_power_config_t*) data)->value);
!     this->Publish(this->actarray_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_REQ_POWER);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_REQ_BRAKES,this->limb_id))
    {
      // We don't have any brakes
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_REQ_GEOM,this->limb_id))
    {
      player_limb_geom_req_t limbGeom;
***************
*** 2446,2453 ****
      limbGeom.basePos.pz = armOffsetZ;
  
!     this->Publish(this->limb_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_GEOM_REQ, &limbGeom, sizeof (limbGeom), NULL);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_SPEED_REQ,this->limb_id))
    {
      // FIXME - need to figure out what sort of speed support we should 
provide through the IK interface
--- 2446,2453 ----
      limbGeom.basePos.pz = armOffsetZ;
  
!     this->Publish(this->limb_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_REQ_GEOM, &limbGeom, sizeof (limbGeom), NULL);
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_LIMB_REQ_SPEED,this->limb_id))
    {
      // FIXME - need to figure out what sort of speed support we should 
provide through the IK interface
***************
*** 2461,2468 ****
      }
  
!     this->Publish(this->limb_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_SPEED_REQ);
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, 
PLAYER_BUMPER_GET_GEOM, this->bumper_id))
    {
      /* Return the bumper geometry. */
--- 2461,2468 ----
      }
  
!     this->Publish(this->limb_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_LIMB_REQ_SPEED);
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, 
PLAYER_BUMPER_REQ_GET_GEOM, this->bumper_id))
    {
      /* Return the bumper geometry. */
***************
*** 2485,2493 ****
  
      this->Publish(this->bumper_id, resp_queue,
!                   PLAYER_MSGTYPE_RESP_ACK, PLAYER_BUMPER_GET_GEOM,
                    (void*)&geom, sizeof(geom), NULL);
      return(0);
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_GET_GEOM_REQ,this->lift_id))
    {
      player_actarray_geom_t aaGeom;
--- 2485,2493 ----
  
      this->Publish(this->bumper_id, resp_queue,
!                   PLAYER_MSGTYPE_RESP_ACK, PLAYER_BUMPER_REQ_GET_GEOM,
                    (void*)&geom, sizeof(geom), NULL);
      return(0);
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_REQ,PLAYER_ACTARRAY_REQ_GET_GEOM,this->lift_id))
    {
      player_actarray_geom_t aaGeom;
***************
*** 2504,2508 ****
      aaGeom.actuators[0].hasbrakes = 0;
  
!     this->Publish(this->lift_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_GET_GEOM_REQ, &aaGeom, sizeof (aaGeom), NULL);
      return 0;
    }
--- 2504,2508 ----
      aaGeom.actuators[0].hasbrakes = 0;
  
!     this->Publish(this->lift_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, 
PLAYER_ACTARRAY_REQ_GET_GEOM, &aaGeom, sizeof (aaGeom), NULL);
      return 0;
    }
***************
*** 2733,2737 ****
    P2OSPacket packet;
  
!   if (!(lastActArrayCmd == PLAYER_ACTARRAY_POS_CMD) || ((lastActArrayCmd == 
PLAYER_ACTARRAY_POS_CMD) &&
         (cmd.joint != lastActArrayPosCmd.joint || cmd.position != 
lastActArrayPosCmd.position)))
    {
--- 2733,2737 ----
    P2OSPacket packet;
  
!   if (!(lastActArrayCmd == PLAYER_ACTARRAY_CMD_POS) || ((lastActArrayCmd == 
PLAYER_ACTARRAY_CMD_POS) &&
         (cmd.joint != lastActArrayPosCmd.joint || cmd.position != 
lastActArrayPosCmd.position)))
    {
***************
*** 2751,2755 ****
    P2OSPacket packet;
  
!   if ((lastActArrayCmd == PLAYER_ACTARRAY_POS_CMD) || (!(lastActArrayCmd == 
PLAYER_ACTARRAY_POS_CMD) &&
         (cmd.joint != lastActArrayHomeCmd.joint)))
    {
--- 2751,2755 ----
    P2OSPacket packet;
  
!   if ((lastActArrayCmd == PLAYER_ACTARRAY_CMD_POS) || (!(lastActArrayCmd == 
PLAYER_ACTARRAY_CMD_POS) &&
         (cmd.joint != lastActArrayHomeCmd.joint)))
    {
***************
*** 2765,2785 ****
  int P2OS::HandleActArrayCommand (player_msghdr * hdr, void * data)
  {
!   if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_POS_CMD, this->actarray_id))
    {
      player_actarray_position_cmd_t cmd;
      cmd = *(player_actarray_position_cmd_t*) data;
      this->HandleActArrayPosCmd (cmd);
!     lastActArrayCmd = PLAYER_ACTARRAY_POS_CMD;
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_HOME_CMD, this->actarray_id))
    {
      player_actarray_home_cmd_t cmd;
      cmd = *(player_actarray_home_cmd_t*) data;
      this->HandleActArrayHomeCmd (cmd);
!     lastActArrayCmd = PLAYER_ACTARRAY_HOME_CMD;
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_MULTI_POS_CMD, this->actarray_id))
    {
      player_actarray_multi_position_cmd_t cmd = 
*(player_actarray_multi_position_cmd_t*) data;
--- 2765,2785 ----
  int P2OS::HandleActArrayCommand (player_msghdr * hdr, void * data)
  {
!   if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_POS, this->actarray_id))
    {
      player_actarray_position_cmd_t cmd;
      cmd = *(player_actarray_position_cmd_t*) data;
      this->HandleActArrayPosCmd (cmd);
!     lastActArrayCmd = PLAYER_ACTARRAY_CMD_POS;
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_HOME, this->actarray_id))
    {
      player_actarray_home_cmd_t cmd;
      cmd = *(player_actarray_home_cmd_t*) data;
      this->HandleActArrayHomeCmd (cmd);
!     lastActArrayCmd = PLAYER_ACTARRAY_CMD_HOME;
      return 0;
    }
!   else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_ACTARRAY_CMD_MULTI_POS, this->actarray_id))
    {
      player_actarray_multi_position_cmd_t cmd = 
*(player_actarray_multi_position_cmd_t*) data;
***************
*** 2791,2795 ****
        this->HandleActArrayPosCmd (singleCmd);
      }
!     lastActArrayCmd = PLAYER_ACTARRAY_MULTI_POS_CMD;
    }
  
--- 2791,2795 ----
        this->HandleActArrayPosCmd (singleCmd);
      }
!     lastActArrayCmd = PLAYER_ACTARRAY_CMD_MULTI_POS;
    }
  
***************
*** 2966,2980 ****
  int P2OS::HandleLimbCommand (player_msghdr *hdr, void *data)
  {
!   
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_HOME_CMD,this->limb_id))
    {
      this->HandleLimbHomeCmd ();
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_STOP_CMD,this->limb_id))
    {
      this->HandleLimbStopCmd ();
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_SETPOSE_CMD,this->limb_id))
    {
      player_limb_setpose_cmd_t cmd;
--- 2966,2980 ----
  int P2OS::HandleLimbCommand (player_msghdr *hdr, void *data)
  {
!   
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_CMD_HOME,this->limb_id))
    {
      this->HandleLimbHomeCmd ();
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_CMD_STOP,this->limb_id))
    {
      this->HandleLimbStopCmd ();
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_CMD_SETPOSE,this->limb_id))
    {
      player_limb_setpose_cmd_t cmd;
***************
*** 2983,3000 ****
      return 0;
    }
- //   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_SETPOSITION_CMD,this->limb_id))
- //   {
- //     player_limb_setposition_cmd_t cmd;
- //     cmd = *(player_limb_setposition_cmd_t*) data;
- //     this->HandleLimbSetPositionCmd (cmd);
- //     retVal = 0;
- //   }
- //   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_LIMB_VECMOVE_CMD,this->limb_id))
- //   {
- //     player_limb_vecmove_cmd_t cmd;
- //     cmd = *(player_limb_vecmove_cmd_t*) data;
- //     this->HandleLimbVecMoveCmd (cmd);
- //     retVal = 0;
- //   }
    return -1;
  }
--- 2983,2986 ----
***************
*** 3008,3012 ****
    P2OSPacket packet;
  
!   
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_ACTARRAY_POS_CMD,this->lift_id))
    {
      player_actarray_position_cmd_t cmd;
--- 2994,2998 ----
    P2OSPacket packet;
  
!   
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_ACTARRAY_CMD_POS,this->lift_id))
    {
      player_actarray_position_cmd_t cmd;
***************
*** 3017,3021 ****
        return -1;
  
!     if (lastLiftCmd == PLAYER_ACTARRAY_POS_CMD && lastLiftPosCmd.position == 
cmd.position)
        return 0;
  
--- 3003,3007 ----
        return -1;
  
!     if (lastLiftCmd == PLAYER_ACTARRAY_CMD_POS && lastLiftPosCmd.position == 
cmd.position)
        return 0;
  
***************
*** 3072,3083 ****
      }
  
!     lastLiftCmd = PLAYER_ACTARRAY_POS_CMD;
      lastLiftPosCmd = cmd;
      sippacket->lastLiftPos = cmd.position;
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_ACTARRAY_HOME_CMD,this->lift_id))
    {
!     if (lastLiftCmd == PLAYER_ACTARRAY_HOME_CMD)
        return 0;
  
--- 3058,3069 ----
      }
  
!     lastLiftCmd = PLAYER_ACTARRAY_CMD_POS;
      lastLiftPosCmd = cmd;
      sippacket->lastLiftPos = cmd.position;
      return 0;
    }
!   else 
if(Message::MatchMessage(hdr,PLAYER_MSGTYPE_CMD,PLAYER_ACTARRAY_CMD_HOME,this->lift_id))
    {
!     if (lastLiftCmd == PLAYER_ACTARRAY_CMD_HOME)
        return 0;
  
***************
*** 3089,3093 ****
      packet.Build (command, 4);
      SendReceive (&packet);
!     lastLiftCmd = PLAYER_ACTARRAY_HOME_CMD;
      lastLiftPosCmd.position = 1.0f;
      return 0;
--- 3075,3079 ----
      packet.Build (command, 4);
      SendReceive (&packet);
!     lastLiftCmd = PLAYER_ACTARRAY_CMD_HOME;
      lastLiftPosCmd.position = 1.0f;
      return 0;
***************
*** 3281,3285 ****
      retVal = 0;
    }
!   else if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_AUDIO_SAMPLE_PLAY_CMD, this->audio_id))
    {
      // get and send the latest audio command, if it's new
--- 3267,3271 ----
      retVal = 0;
    }
!   else if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_AUDIO_CMD_SAMPLE_PLAY, this->audio_id))
    {
      // get and send the latest audio command, if it's new


-------------------------------------------------------------------------
This SF.net email is sponsored by: Splunk Inc.
Still grepping through log files to find problems?  Stop.
Now Search log events and configuration files using AJAX and a browser.
Download your FREE copy of Splunk now >>  http://get.splunk.com/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to