Update of /cvsroot/playerstage/code/player/server/drivers/limb
In directory sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv30199/server/drivers/limb
Modified Files:
eeDHcontroller.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: eeDHcontroller.cc
===================================================================
RCS file:
/cvsroot/playerstage/code/player/server/drivers/limb/eeDHcontroller.cc,v
retrieving revision 1.1
retrieving revision 1.2
diff -C2 -d -r1.1 -r1.2
*** eeDHcontroller.cc 22 May 2007 22:11:03 -0000 1.1
--- eeDHcontroller.cc 20 Aug 2007 06:37:27 -0000 1.2
***************
*** 42,51 ****
When a positioning command of the limb is received via
! PLAYER_LIMB_SETPOSITION_CMD or PLAYER_LIMB_SETPOSE_CMD, the driver computes
the joint commands and sends them in ascending order (base to end effector)
! to the actarray interface using PLAYER_ACTARRAY_POS_CMD.
! When a homing command of the limb is received via PLAYER_LIMB_HOME_CMD, the
! driver will send a PLAYER_ACTARRAY_HOME_CMD to every joint provided by the
actarray interface in descending order (end effector to base).
--- 42,51 ----
When a positioning command of the limb is received via
! PLAYER_LIMB_CMD_SETPOSITION or PLAYER_LIMB_CMD_SETPOSE, the driver computes
the joint commands and sends them in ascending order (base to end effector)
! to the actarray interface using PLAYER_ACTARRAY_CMD_POS.
! When a homing command of the limb is received via PLAYER_LIMB_CMD_HOME, the
! driver will send a PLAYER_ACTARRAY_CMD_HOME to every joint provided by the
actarray interface in descending order (end effector to base).
***************
*** 68,72 ****
@par Configuration requests
! - PLAYER_LIMB_SPEED_REQ
@par Configuration file options
--- 68,72 ----
@par Configuration requests
! - PLAYER_LIMB_REQ_SPEED
@par Configuration file options
***************
*** 500,504 ****
this->actarray_device->PutMsg (this->InQueue,
PLAYER_MSGTYPE_CMD,
! PLAYER_ACTARRAY_HOME_CMD,
(void*)&cmd,
sizeof (cmd), NULL);
--- 500,504 ----
this->actarray_device->PutMsg (this->InQueue,
PLAYER_MSGTYPE_CMD,
! PLAYER_ACTARRAY_CMD_HOME,
(void*)&cmd,
sizeof (cmd), NULL);
***************
*** 582,586 ****
this->actarray_device->PutMsg (this->InQueue,
PLAYER_MSGTYPE_CMD,
! PLAYER_ACTARRAY_POS_CMD,
(void*)&cmd,
sizeof (cmd), NULL);
--- 582,586 ----
this->actarray_device->PutMsg (this->InQueue,
PLAYER_MSGTYPE_CMD,
! PLAYER_ACTARRAY_CMD_POS,
(void*)&cmd,
sizeof (cmd), NULL);
***************
*** 616,623 ****
// Check for capabilities requests first
HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_REQ, PLAYER_CAPABILTIES_REQ);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_SPEED_REQ);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_SETPOSE_CMD);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_SETPOSITION_CMD);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_HOME_CMD);
// First look whether we have incoming data from the actarray interface
--- 616,623 ----
// Check for capabilities requests first
HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_REQ, PLAYER_CAPABILTIES_REQ);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_REQ, PLAYER_LIMB_REQ_SPEED);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_SETPOSE);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_SETPOSITION);
! HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data,
PLAYER_MSGTYPE_CMD, PLAYER_LIMB_CMD_HOME);
// First look whether we have incoming data from the actarray interface
***************
*** 632,636 ****
// Set the desired position to the actarray driver
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_SETPOSE_CMD, device_addr))
{
player_limb_setpose_cmd_t & command =
--- 632,636 ----
// Set the desired position to the actarray driver
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_CMD_SETPOSE, device_addr))
{
player_limb_setpose_cmd_t & command =
***************
*** 657,661 ****
// Set the desired position to the actarray driver
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_SETPOSITION_CMD, device_addr))
{
player_limb_setposition_cmd_t & command =
--- 657,661 ----
// Set the desired position to the actarray driver
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_CMD_SETPOSITION, device_addr))
{
player_limb_setposition_cmd_t & command =
***************
*** 680,684 ****
// Home the limb (we do this by homing all the joints)
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_HOME_CMD, device_addr))
{
homing_thread = true;
--- 680,684 ----
// Home the limb (we do this by homing all the joints)
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
! PLAYER_LIMB_CMD_HOME, device_addr))
{
homing_thread = true;
***************
*** 691,695 ****
// POWER_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_POWER_REQ, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
--- 691,695 ----
// POWER_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_REQ_POWER, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
***************
*** 699,703 ****
// BRAKES_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_BRAKES_REQ, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
--- 699,703 ----
// BRAKES_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_REQ_BRAKES, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
***************
*** 707,711 ****
// GEOM_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_GEOM_REQ, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
--- 707,711 ----
// GEOM_REQ not implemented
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_REQ_GEOM, device_addr))
{
Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype);
***************
*** 715,719 ****
// SPEED_REQ - Set the speed on all joints equal to the EE
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_SPEED_REQ, device_addr))
{
player_limb_speed_req_t & cfg =
--- 715,719 ----
// SPEED_REQ - Set the speed on all joints equal to the EE
else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
! PLAYER_LIMB_REQ_SPEED, device_addr))
{
player_limb_speed_req_t & cfg =
***************
*** 730,734 ****
if (!(msg = this->actarray_device->Request (this->InQueue,
PLAYER_MSGTYPE_REQ,
! PLAYER_ACTARRAY_SPEED_REQ,
(void*)&act_cfg,
sizeof (act_cfg), NULL,
false)))
--- 730,734 ----
if (!(msg = this->actarray_device->Request (this->InQueue,
PLAYER_MSGTYPE_REQ,
! PLAYER_ACTARRAY_REQ_SPEED,
(void*)&act_cfg,
sizeof (act_cfg), NULL,
false)))
-------------------------------------------------------------------------
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