Revision: 7278 http://playerstage.svn.sourceforge.net/playerstage/?rev=7278&view=rev Author: thjc Date: 2009-01-16 22:32:00 +0000 (Fri, 16 Jan 2009)
Log Message: ----------- removed empty structures from player Modified Paths: -------------- code/player/trunk/client_libs/libplayerc/client.c code/player/trunk/client_libs/libplayerc/dev_gripper.c code/player/trunk/client_libs/libplayerc/dev_limb.c code/player/trunk/client_libs/libplayerc/dev_position3d.c code/player/trunk/libplayercore/interfaces/001_player.def code/player/trunk/libplayercore/interfaces/003_gripper.def code/player/trunk/libplayercore/interfaces/004_position2d.def code/player/trunk/libplayercore/interfaces/030_position3d.def code/player/trunk/libplayercore/interfaces/045_log.def code/player/trunk/libplayercore/interfaces/054_limb.def code/player/trunk/libplayercore/interfaces/055_graphics2d.def code/player/trunk/libplayercore/interfaces/056_rfid.def code/player/trunk/libplayercore/interfaces/058_graphics3d.def code/player/trunk/libplayercore/player.h code/player/trunk/libplayercore/playerinterfacegen.py code/player/trunk/server/drivers/mixed/botrics/obot.cc Modified: code/player/trunk/client_libs/libplayerc/client.c =================================================================== --- code/player/trunk/client_libs/libplayerc/client.c 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/client_libs/libplayerc/client.c 2009-01-16 22:32:00 UTC (rev 7278) @@ -551,13 +551,12 @@ playerc_client_requestdata(playerc_client_t* client) { int ret; - player_null_t req; if(client->mode != PLAYER_DATAMODE_PULL || client->data_requested) return(0); ret = playerc_client_request(client, NULL, PLAYER_PLAYER_REQ_DATA, - &req, NULL); + NULL, NULL); if(ret == 0) { client->data_requested = 1; Modified: code/player/trunk/client_libs/libplayerc/dev_gripper.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_gripper.c 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/client_libs/libplayerc/dev_gripper.c 2009-01-16 22:32:00 UTC (rev 7278) @@ -108,46 +108,31 @@ // Command the gripper to open int playerc_gripper_open_cmd (playerc_gripper_t *device) { - player_null_t cmd; - - memset (&cmd, 0, sizeof (cmd)); - return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_OPEN, &cmd, NULL); + return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_OPEN, NULL, NULL); } // Command the gripper to close int playerc_gripper_close_cmd (playerc_gripper_t *device) { - player_null_t cmd; - - memset (&cmd, 0, sizeof (cmd)); - return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_CLOSE, &cmd, NULL); + return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_CLOSE, NULL, NULL); } // Command the gripper to stop int playerc_gripper_stop_cmd (playerc_gripper_t *device) { - player_null_t cmd; - - memset (&cmd, 0, sizeof (cmd)); - return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_STOP, &cmd, NULL); + return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_STOP, NULL, NULL); } // Command the gripper to store int playerc_gripper_store_cmd (playerc_gripper_t *device) { - player_null_t cmd; - - memset (&cmd, 0, sizeof (cmd)); - return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_STORE, &cmd, NULL); + return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_STORE, NULL, NULL); } // Command the gripper to retrieve int playerc_gripper_retrieve_cmd (playerc_gripper_t *device) { - player_null_t cmd; - - memset (&cmd, 0, sizeof (cmd)); - return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_RETRIEVE, &cmd, NULL); + return playerc_client_write (device->info.client, &device->info, PLAYER_GRIPPER_CMD_RETRIEVE, NULL, NULL); } // Get the geometry. The writes the result into the proxy Modified: code/player/trunk/client_libs/libplayerc/dev_limb.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_limb.c 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/client_libs/libplayerc/dev_limb.c 2009-01-16 22:32:00 UTC (rev 7278) @@ -125,25 +125,17 @@ // Command the end effector to move home int playerc_limb_home_cmd(playerc_limb_t *device) { - player_null_t cmd; - - memset(&cmd, 0, sizeof(cmd)); - return playerc_client_write(device->info.client, &device->info, PLAYER_LIMB_CMD_HOME, - &cmd, NULL); + NULL, NULL); } // Command the end effector to stop immediatly int playerc_limb_stop_cmd(playerc_limb_t *device) { - player_null_t cmd; - - memset(&cmd, 0, sizeof(cmd)); - return playerc_client_write(device->info.client, &device->info, PLAYER_LIMB_CMD_STOP, - &cmd, NULL); + NULL, NULL); } // Command the end effector to move to a specified pose Modified: code/player/trunk/client_libs/libplayerc/dev_position3d.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_position3d.c 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/client_libs/libplayerc/dev_position3d.c 2009-01-16 22:32:00 UTC (rev 7278) @@ -193,7 +193,7 @@ //TODO: Actually store the geometry player_position3d_geom_t_free(config); - + return 0; } @@ -324,14 +324,8 @@ int playerc_position3d_reset_odom(playerc_position3d_t *device) { - player_position3d_reset_odom_config_t config; - - memset(&config, 0, sizeof(config)); - - - return playerc_client_request(device->info.client, &device->info, PLAYER_POSITION3D_REQ_RESET_ODOM, - &config,NULL); + NULL,NULL); } Modified: code/player/trunk/libplayercore/interfaces/001_player.def =================================================================== --- code/player/trunk/libplayercore/interfaces/001_player.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/001_player.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -21,14 +21,14 @@ client can request a single round of data by sending a zero-argument request with type code @p PLAYER_PLAYER_REQ_DATA. The response will be a zero-length acknowledgement. */ -message { REQ, DATA, 4, player_null_t }; +message { REQ, DATA, 4, NULL }; message { REQ, DATAMODE, 5, player_device_datamode_req_t }; message { REQ, AUTH, 7, player_device_auth_req_t }; message { REQ, NAMESERVICE, 8, player_device_nameservice_req_t }; message { REQ, ADD_REPLACE_RULE, 10, player_add_replace_rule_req_t }; -message { SYNCH, OK, 1, player_null_t }; +message { SYNCH, OK, 1, NULL }; message { SYNCH, OVERFLOW, 2, player_uint32_t }; Modified: code/player/trunk/libplayercore/interfaces/003_gripper.def =================================================================== --- code/player/trunk/libplayercore/interfaces/003_gripper.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/003_gripper.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -20,28 +20,28 @@ /** @brief Command: Open (@ref PLAYER_GRIPPER_CMD_OPEN) Tells the gripper to open. */ -message { CMD, OPEN, 1, player_null_t }; +message { CMD, OPEN, 1, NULL }; /** @brief Command: Close (@ref PLAYER_GRIPPER_CMD_CLOSE) Tells the gripper to close. */ -message { CMD, CLOSE, 2, player_null_t }; +message { CMD, CLOSE, 2, NULL }; /** @brief Command: Stop (@ref PLAYER_GRIPPER_CMD_STOP) Tells the gripper to stop. */ -message { CMD, STOP, 3, player_null_t }; +message { CMD, STOP, 3, NULL }; /** @brief Command: Store (@ref PLAYER_GRIPPER_CMD_STORE) Tells the gripper to store whatever it is holding. */ -message { CMD, STORE, 4, player_null_t }; +message { CMD, STORE, 4, NULL }; /** @brief Command: Retrieve (@ref PLAYER_GRIPPER_CMD_RETRIEVE) Tells the gripper to retrieve a stored object (so that it can be put back into the world). The opposite of store. */ -message { CMD, RETRIEVE, 5, player_null_t }; +message { CMD, RETRIEVE, 5, NULL }; /** Gripper state: open */ Modified: code/player/trunk/libplayercore/interfaces/004_position2d.def =================================================================== --- code/player/trunk/libplayercore/interfaces/004_position2d.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/004_position2d.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -191,7 +191,7 @@ To reset the robot's odometry to @f$(x, y, yaw) = (0,0,0)@f$, send a @ref PLAYER_POSITION2D_REQ_RESET_ODOM request. Null response. */ - message { REQ, RESET_ODOM, 6, player_null_t }; + message { REQ, RESET_ODOM, 6, NULL }; /** @brief Request/reply: Set velocity PID parameters. * Modified: code/player/trunk/libplayercore/interfaces/030_position3d.def =================================================================== --- code/player/trunk/libplayercore/interfaces/030_position3d.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/030_position3d.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -24,7 +24,7 @@ /** Request/reply subtype: position mode */ message { REQ, POSITION_MODE, 4, player_position3d_position_mode_req_t }; /** Request/reply subtype: reset odometry */ -message { REQ, RESET_ODOM, 5, player_position3d_set_odom_req_t }; +message { REQ, RESET_ODOM, 5, NULL }; /** Request/reply subtype: set odometry */ message { REQ, SET_ODOM, 6, player_position3d_set_odom_req_t }; /** Request/reply subtype: set speed PID params */ @@ -139,9 +139,6 @@ To reset the robot's odometry to @f$(x,y,\theta) = (0,0,0)@f$, send a @ref PLAYER_POSITION3D_RESET_ODOM request. Null response. */ -typedef struct player_position3d_reset_odom_config -{ -} player_position3d_reset_odom_config_t; /** @brief Request/reply: Set velocity PID parameters. * Modified: code/player/trunk/libplayercore/interfaces/045_log.def =================================================================== --- code/player/trunk/libplayercore/interfaces/045_log.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/045_log.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -14,7 +14,7 @@ /** Request/reply subtype: get state */ message { REQ, GET_STATE, 3, player_log_get_state_t }; /** Request/reply subtype: rewind */ -message { REQ, SET_READ_REWIND, 4, player_log_set_read_rewind_t }; +message { REQ, SET_READ_REWIND, 4, NULL }; /** Request/reply subtype: set filename to write */ message { REQ, SET_FILENAME, 5, player_log_set_filename_t }; @@ -50,10 +50,8 @@ To rewind log playback to beginning of logfile, send a @ref PLAYER_LOG_REQ_SET_READ_REWIND request. Does not affect playback state (i.e., whether it is started or stopped. Null response. */ -typedef struct player_log_set_read_rewind -{ -} player_log_set_read_rewind_t; + /** @brief Request/reply: Get state. To find out whether logging/playback is enabled or disabled, send a null Modified: code/player/trunk/libplayercore/interfaces/054_limb.def =================================================================== --- code/player/trunk/libplayercore/interfaces/054_limb.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/054_limb.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -23,11 +23,11 @@ /** @brief Command: home (@ref PLAYER_LIMB_HOME_CMD) Tells the end effector to return to its home position. */ -message { CMD, HOME, 1, player_null_t }; +message { CMD, HOME, 1, NULL }; /** @brief Command: stop (@ref PLAYER_LIMB_STOP_CMD) Tells the limb to stop moving immediatly. */ -message { CMD, STOP, 2, player_null_t }; +message { CMD, STOP, 2, NULL }; /** Command subtype: set pose */ message { CMD, SETPOSE, 3, player_limb_setpose_cmd_t }; /** Command subtype: set position */ Modified: code/player/trunk/libplayercore/interfaces/055_graphics2d.def =================================================================== --- code/player/trunk/libplayercore/interfaces/055_graphics2d.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/055_graphics2d.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -8,7 +8,7 @@ } /** Command subtype: clear the drawing area (send an empty message) */ -message { CMD, CLEAR, 1, player_null_t }; +message { CMD, CLEAR, 1, NULL }; /** Command subtype: draw points */ message { CMD, POINTS, 2, player_graphics2d_cmd_points_t }; /** Command subtype: draw a polyline */ Modified: code/player/trunk/libplayercore/interfaces/056_rfid.def =================================================================== --- code/player/trunk/libplayercore/interfaces/056_rfid.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/056_rfid.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -10,13 +10,13 @@ message { DATA, TAGS, 1, player_rfid_data_t }; /** Request/reply: put the reader in sleep mode (0) or wake it up (1). */ -message { REQ, POWER, 1, player_null_t }; +message { REQ, POWER, 1, NULL }; /** Request/reply: read data from the RFID tag - to be implemented. */ -message { REQ, READTAG, 2, player_null_t }; +message { REQ, READTAG, 2, NULL }; /** Request/reply: write data to the RFID tag - to be implemented. */ -message { REQ, WRITETAG, 3, player_null_t }; +message { REQ, WRITETAG, 3, NULL }; /** Request/reply: lock data blocks of a RFID tag - to be implemented. */ -message { REQ, LOCKTAG, 4, player_null_t }; +message { REQ, LOCKTAG, 4, NULL }; /** @brief Structure describing a single RFID tag. */ Modified: code/player/trunk/libplayercore/interfaces/058_graphics3d.def =================================================================== --- code/player/trunk/libplayercore/interfaces/058_graphics3d.def 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/interfaces/058_graphics3d.def 2009-01-16 22:32:00 UTC (rev 7278) @@ -12,7 +12,7 @@ } /** Command subtype: clear the drawing area (send an empty message) */ -message { CMD, CLEAR, 1, player_null_t }; +message { CMD, CLEAR, 1, NULL }; /** Command subtype: draw items */ message { CMD, DRAW, 2, player_graphics3d_cmd_draw_t }; /** Command subtype: translate coordinate system */ @@ -20,9 +20,9 @@ /** Command subtype: rotate coordinate system */ message { CMD, ROTATE, 4, player_graphics3d_cmd_rotate_t }; /** Command subtype: push current coordinate system onto stack */ -message { CMD, PUSH, 5, player_null_t }; +message { CMD, PUSH, 5, NULL }; /** Command subtype: pop coordinate system from stack to become current */ -message { CMD, POP, 6, player_null_t }; +message { CMD, POP, 6, NULL }; /** Drawmode: enumeration that defines the drawing mode */ Modified: code/player/trunk/libplayercore/player.h =================================================================== --- code/player/trunk/libplayercore/player.h 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/player.h 2009-01-16 22:32:00 UTC (rev 7278) @@ -176,11 +176,6 @@ * These structures often appear inside other structures. * @{ */ -/** @brief A null structure for parsing completeness */ -typedef struct player_null -{ -} player_null_t; - /** @brief A point in the plane */ typedef struct player_point_2d { Modified: code/player/trunk/libplayercore/playerinterfacegen.py =================================================================== --- code/player/trunk/libplayercore/playerinterfacegen.py 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/libplayercore/playerinterfacegen.py 2009-01-16 22:32:00 UTC (rev 7278) @@ -132,8 +132,9 @@ """ % {"interface_name": interface_name} print "\n /* %s messages */" % interface_name for m in interface_messages: - print " {", interface_def, ",", m.msg_type, ",", m.msg_subtype_string, "," - print " (player_pack_fn_t)%(dt_base)s_pack, (player_copy_fn_t)%(dt)s_copy, (player_cleanup_fn_t)%(dt)s_cleanup,(player_clone_fn_t)%(dt)s_clone,(player_free_fn_t)%(dt)s_free,(player_sizeof_fn_t)%(dt)s_sizeof}," % { "dt_base": m.datatype[:-2], "dt": m.datatype} + if m.datatype != "NULL": + print " {", interface_def, ",", m.msg_type, ",", m.msg_subtype_string, "," + print " (player_pack_fn_t)%(dt_base)s_pack, (player_copy_fn_t)%(dt)s_copy, (player_cleanup_fn_t)%(dt)s_cleanup,(player_clone_fn_t)%(dt)s_clone,(player_free_fn_t)%(dt)s_free,(player_sizeof_fn_t)%(dt)s_sizeof}," % { "dt_base": m.datatype[:-2], "dt": m.datatype} if plugin: print """ /* This NULL element signals the end of the list */ Modified: code/player/trunk/server/drivers/mixed/botrics/obot.cc =================================================================== --- code/player/trunk/server/drivers/mixed/botrics/obot.cc 2009-01-16 21:58:55 UTC (rev 7277) +++ code/player/trunk/server/drivers/mixed/botrics/obot.cc 2009-01-16 22:32:00 UTC (rev 7278) @@ -137,7 +137,7 @@ static void StopRobot(void* obotdev); -class Obot : public ThreadedDriver +class Obot : public ThreadedDriver { private: // this function will be run in a separate thread @@ -776,12 +776,6 @@ PLAYER_POSITION2D_REQ_RESET_ODOM, this->position_addr)) { - if(hdr->size != sizeof(player_null_t)) - { - PLAYER_WARN("Arg to odometry reset requests wrong size; ignoring"); - return(-1); - } - // Just overwrite our current odometric pose. this->px = 0.0; this->py = 0.0; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------------ This SF.net email is sponsored by: SourcForge Community SourceForge wants to tell your story. http://p.sf.net/sfu/sf-spreadtheword _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit