stage.h
Go to the documentation of this file.00001 #ifndef STG_H 00002 #define STG_H 00003 /* 00004 * Stage : a multi-robot simulator. 00005 * 00006 * Copyright (C) 2001-2004 Richard Vaughan, Andrew Howard and Brian 00007 * Gerkey for the Player/Stage Project 00008 * http://playerstage.sourceforge.net 00009 * 00010 * This program is free software; you can redistribute it and/or modify 00011 * it under the terms of the GNU General Public License as published by 00012 * the Free Software Foundation; either version 2 of the License, or 00013 * (at your option) any later version. 00014 * 00015 * This program is distributed in the hope that it will be useful, 00016 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00017 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00018 * GNU General Public License for more details. 00019 * 00020 * You should have received a copy of the GNU General Public License 00021 * along with this program; if not, write to the Free Software 00022 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00023 * 00024 */ 00025 00026 /* File: stage.h 00027 * Desc: External header file for the Stage library 00028 * Authors: Richard Vaughan vaughan@sfu.ca 00029 * Andrew Howard ahowards@usc.edu 00030 * Brian Gerkey gerkey@stanford.edu 00031 * Date: 1 June 2003 00032 * CVS: $Id: stage.h,v 1.188.2.3 2007/10/02 21:04:32 gerkey Exp $ 00033 */ 00034 00035 00043 #include <unistd.h> 00044 #include <stdint.h> // for portable int types eg. uint32_t 00045 #include <sys/types.h> 00046 #include <sys/time.h> 00047 #include <glib.h> // we use GLib's data structures extensively 00048 00049 #ifdef __cplusplus 00050 extern "C" { 00051 #endif 00052 00091 #define FiducialNone 0 00092 00093 #define STG_TOKEN_MAX 64 00094 00103 typedef int stg_id_t; 00104 00106 typedef double stg_meters_t; 00107 00109 typedef double stg_radians_t; 00110 00112 typedef unsigned long stg_msec_t; 00113 00115 typedef double stg_kg_t; // Kilograms (mass) 00116 00118 typedef double stg_joules_t; 00119 00121 typedef double stg_watts_t; 00122 00124 typedef int stg_bool_t; 00125 00126 //typedef double stg_friction_t; 00127 00129 typedef uint32_t stg_color_t; 00130 00133 //typedef int stg_obstacle_return_t; 00134 00137 //typedef int stg_blob_return_t; 00138 00140 //typedef int stg_fiducial_return_t; 00141 00142 //typedef int stg_ranger_return_t; 00143 00144 //typedef enum { STG_GRIP_NO = 0, STG_GRIP_YES } stg_gripper_return_t; 00145 00148 typedef struct 00149 { 00150 stg_meters_t x, y; 00151 } stg_size_t; 00152 00156 typedef struct 00157 { 00158 stg_meters_t x, y, a; 00159 } stg_pose_t; 00160 00163 typedef stg_pose_t stg_velocity_t; 00164 00168 typedef struct 00169 { 00170 stg_pose_t pose; 00171 stg_size_t size; 00172 } stg_geom_t; 00173 00175 typedef struct 00176 { 00177 double min; //< smallest value in range 00178 double max; //< largest value in range 00179 } stg_bounds_t; 00180 00182 typedef struct 00183 { 00184 stg_bounds_t range; //< min and max range of sensor 00185 stg_radians_t angle; //< width of viewing angle of sensor 00186 } stg_fov_t; 00187 00189 typedef struct 00190 { 00191 stg_radians_t pan; 00192 stg_radians_t tilt; 00193 stg_radians_t zoom; 00194 } stg_ptz_t; 00195 // end types 00197 00198 00199 // GUIFEATURES ------------------------------------------------------- 00200 00201 00202 // forward declare struct types from player_internal.h 00203 struct _stg_model; 00204 struct _stg_matrix; 00205 struct _gui_window; 00206 struct _stg_world; 00207 00208 typedef struct _stg_model stg_model_t; // defined in stage_internal. 00209 typedef struct _stg_world stg_world_t; 00210 00211 00212 00215 stg_msec_t stg_timenow( void ); 00216 00222 int stg_init( int argc, char** argv ); 00223 00224 00226 int stg_quit_test( void ); 00227 00230 void stg_quit_request( void ); 00231 00232 00236 const char* stg_version_string( void ); 00237 00238 00239 // POINTS --------------------------------------------------------- 00247 typedef struct 00248 { 00249 stg_meters_t x, y; 00250 } stg_point_t; 00251 00254 stg_point_t* stg_points_create( size_t count ); 00255 00257 void stg_points_destroy( stg_point_t* pts ); 00258 00261 // POLYLINES --------------------------------------------------------- 00262 00270 typedef struct 00271 { 00272 stg_point_t* points; 00273 size_t points_count; 00274 } stg_polyline_t; 00275 00278 // POLYGONS --------------------------------------------------------- 00279 00288 typedef struct 00289 { 00291 GArray* points; 00292 00294 stg_bool_t unfilled; 00295 00297 stg_color_t color; 00298 00300 stg_size_t bbox; 00301 00302 void* _data; // temporary internal use only 00303 } stg_polygon_t; 00304 00305 00307 stg_polygon_t* stg_polygons_create( int count ); 00308 00310 void stg_polygons_destroy( stg_polygon_t* p, size_t count ); 00311 00313 stg_polygon_t* stg_unit_polygon_create( void ); 00314 00318 void stg_polygon_set_points( stg_polygon_t* poly, stg_point_t* pts, size_t count ); 00321 void stg_polygon_append_points( stg_polygon_t* poly, stg_point_t* pts, size_t count ); 00322 00325 void stg_polygons_normalize( stg_polygon_t* polys, int num, 00326 double width, double height ); 00327 00329 void stg_polygon_print( stg_polygon_t* poly ); 00330 00332 void stg_polygons_print( stg_polygon_t* polys, unsigned int count ); 00333 00338 stg_polygon_t* stg_polygons_from_image_file( const char* filename, 00339 size_t* poly_count ); 00340 00343 // end property typedefs ------------------------------------------------- 00344 00345 00346 // WORLD -------------------------------------------------------- 00347 00366 stg_world_t* stg_world_create( stg_id_t id, 00367 const char* token, 00368 int sim_interval, 00369 int real_interval, 00370 double ppm, 00371 double width, 00372 double height ); 00373 00377 stg_world_t* stg_world_create_from_file( const char* worldfile_path ); 00378 00381 void stg_world_destroy( stg_world_t* world ); 00382 00385 void stg_world_stop( stg_world_t* world ); 00386 00389 void stg_world_start( stg_world_t* world ); 00390 00397 int stg_world_update( stg_world_t* world, int sleepflag ); 00398 00400 void stg_world_load( stg_world_t* mod ); 00401 00403 void stg_world_save( stg_world_t* mod ); 00404 00407 void stg_world_print( stg_world_t* world ); 00408 00411 void stg_world_set_interval_real( stg_world_t* world, unsigned int val ); 00412 00416 void stg_world_set_interval_sim( stg_world_t* world, unsigned int val ); 00417 00420 stg_model_t* stg_world_get_model( stg_world_t* world, stg_id_t mid ); 00421 00423 stg_model_t* stg_world_model_name_lookup( stg_world_t* world, const char* name ); 00424 00427 // MODEL -------------------------------------------------------- 00428 00429 // group the docs of all the model types 00436 // Movement masks for figures 00437 #define STG_MOVE_TRANS (1 << 0) 00438 #define STG_MOVE_ROT (1 << 1) 00439 #define STG_MOVE_SCALE (1 << 2) 00440 00441 typedef int stg_movemask_t; 00442 00453 typedef int (*stg_model_callback_t)(stg_model_t* mod, void* user ); 00454 00455 void stg_model_add_callback( stg_model_t* mod, 00456 void* member, 00457 stg_model_callback_t cb, 00458 void* user ); 00459 00460 int stg_model_remove_callback( stg_model_t* mod, 00461 void* member, 00462 stg_model_callback_t callback ); 00463 00464 00471 typedef int(*stg_model_initializer_t)(stg_model_t*); 00472 00473 00474 00476 typedef enum 00477 { 00478 LaserTransparent, 00479 LaserVisible, 00480 LaserBright 00481 } stg_laser_return_t; 00482 00484 stg_model_t* stg_model_create( stg_world_t* world, 00485 stg_model_t* parent, 00486 stg_id_t id, 00487 char* typestr ); 00488 00490 void stg_model_destroy( stg_model_t* mod ); 00491 00493 void stg_model_get_global_pose( stg_model_t* mod, stg_pose_t* pose ); 00494 00496 void stg_model_get_global_velocity( stg_model_t* mod, stg_velocity_t* gvel ); 00497 00498 /* set the velocity of a model in the global coordinate system */ 00499 void stg_model_set_global_velocity( stg_model_t* mod, stg_velocity_t* gvel ); 00500 00502 void stg_model_subscribe( stg_model_t* mod ); 00503 00505 void stg_model_unsubscribe( stg_model_t* mod ); 00506 00508 void stg_model_load( stg_model_t* mod ); 00509 00511 void stg_model_save( stg_model_t* mod ); 00512 00514 //const char* stg_model_type_string( stg_model_type_t type ); 00515 00516 // SET properties - use these to set props, don't set them directly 00517 00519 void stg_model_set_global_pose( stg_model_t* mod, stg_pose_t* gpose ); 00520 00522 void stg_model_set_velocity( stg_model_t* mod, stg_velocity_t* vel ); 00523 00525 void stg_model_set_pose( stg_model_t* mod, stg_pose_t* pose ); 00526 00528 void stg_model_set_geom( stg_model_t* mod, stg_geom_t* src ); 00529 00531 void stg_model_set_fiducial_return( stg_model_t* mod, int fid ); 00532 00535 void stg_model_set_fiducial_key( stg_model_t* mod, int key ); 00536 00538 int stg_model_set_parent( stg_model_t* mod, stg_model_t* newparent); 00539 00542 void stg_model_get_geom( stg_model_t* mod, stg_geom_t* dest ); 00543 00545 void stg_model_get_pose( stg_model_t* mod, stg_pose_t* dest ); 00546 00548 void stg_model_get_velocity( stg_model_t* mod, stg_velocity_t* dest ); 00549 00552 stg_polygon_t* stg_model_get_polygons( stg_model_t* mod, size_t* poly_count ); 00553 void stg_model_set_polygons( stg_model_t* mod, 00554 stg_polygon_t* polys, 00555 size_t poly_count ); 00556 00558 void stg_model_set_lines( stg_model_t* mod, 00559 stg_polyline_t* lines, 00560 size_t lines_count ); 00561 00562 // guess what these do? 00563 void stg_model_get_velocity( stg_model_t* mod, stg_velocity_t* dest ); 00564 void stg_model_set_velocity( stg_model_t* mod, stg_velocity_t* vel ); 00565 void stg_model_set_pose( stg_model_t* mod, stg_pose_t* pose ); 00566 void stg_model_get_geom( stg_model_t* mod, stg_geom_t* dest ); 00567 void stg_model_set_geom( stg_model_t* mod, stg_geom_t* geom ); 00568 void stg_model_set_color( stg_model_t* mod, stg_color_t col ); 00569 void stg_model_set_mass( stg_model_t* mod, stg_kg_t mass ); 00570 void stg_model_set_stall( stg_model_t* mod, stg_bool_t stall ); 00571 void stg_model_set_gripper_return( stg_model_t* mod, int val ); 00572 void stg_model_set_laser_return( stg_model_t* mod, int val ); 00573 void stg_model_set_obstacle_return( stg_model_t* mod, int val ); 00574 void stg_model_set_blob_return( stg_model_t* mod, int val ); 00575 void stg_model_set_ranger_return( stg_model_t* mod, int val ); 00576 void stg_model_set_boundary( stg_model_t* mod, int val ); 00577 void stg_model_set_gui_nose( stg_model_t* mod, int val ); 00578 void stg_model_set_gui_mask( stg_model_t* mod, int val ); 00579 void stg_model_set_gui_grid( stg_model_t* mod, int val ); 00580 void stg_model_set_gui_outline( stg_model_t* mod, int val ); 00581 void stg_model_set_watts( stg_model_t* mod, stg_watts_t watts ); 00582 void stg_model_set_map_resolution( stg_model_t* mod, stg_meters_t res ); 00583 00592 int stg_model_set_named_property_int( stg_model_t* mod, 00593 char* name, 00594 size_t len, 00595 int value ); 00596 00605 int stg_model_set_named_property_double( stg_model_t* mod, 00606 char* name, 00607 size_t len, 00608 double value ); 00609 00610 00617 /* void stg_model_set_property( stg_model_t* mod, */ 00618 /* char* key, */ 00619 /* void* data, */ 00620 /* size_t len ); */ 00621 00622 /* /\** @TODO The callback cb will be called with argument arg when the */ 00623 /* property identified by key is set. *\/ */ 00624 /* void stg_model_set_property_callback( stg_model_t* mod, */ 00625 /* char* key, */ 00626 /* stg_property_callback cb, */ 00627 /* void* argn ); */ 00628 00632 void stg_model_print( stg_model_t* mod, char* prefix ); 00633 00636 int stg_model_is_antecedent( stg_model_t* mod, stg_model_t* testmod ); 00637 00640 int stg_model_is_descendent( stg_model_t* mod, stg_model_t* testmod ); 00641 00645 int stg_model_is_related( stg_model_t* mod1, stg_model_t* mod2 ); 00646 00648 stg_model_t* stg_model_root( stg_model_t* mod ); 00649 00651 GPtrArray* stg_model_array_from_tree( stg_model_t* root ); 00652 00654 int stg_model_startup( stg_model_t* mod ); 00655 00657 int stg_model_shutdown( stg_model_t* mod ); 00658 00661 int stg_model_update( stg_model_t* model ); 00662 00666 void stg_model_global_to_local( stg_model_t* mod, stg_pose_t* pose ); 00667 00671 void stg_model_local_to_global( stg_model_t* mod, stg_pose_t* pose ); 00672 00673 int stg_model_fig_clear_cb( stg_model_t* mod, void* data, size_t len, 00674 void* userp ); 00675 00676 void stg_model_set_data( stg_model_t* mod, void* data, size_t len ); 00677 void stg_model_set_cmd( stg_model_t* mod, void* cmd, size_t len ); 00678 void stg_model_set_cfg( stg_model_t* mod, void* cfg, size_t len ); 00679 void* stg_model_get_cfg( stg_model_t* mod, size_t* lenp ); 00680 void* stg_model_get_data( stg_model_t* mod, size_t* lenp ); 00681 void* stg_model_get_cmd( stg_model_t* mod, size_t* lenp ); 00682 00683 00687 void stg_model_add_property_toggles( stg_model_t* mod, 00688 void* member, 00689 stg_model_callback_t callback_on, 00690 void* arg_on, 00691 stg_model_callback_t callback_off, 00692 void* arg_off, 00693 const char* name, 00694 const char* label, 00695 gboolean enabled ); 00696 00697 00698 // BLOBFINDER MODEL -------------------------------------------------------- 00699 00700 #define STG_BLOB_CHANNELS_MAX 16 00701 00704 typedef struct 00705 { 00706 int channel_count; // 0 to STG_BLOBFINDER_CHANNELS_MAX 00707 stg_color_t channels[STG_BLOB_CHANNELS_MAX]; 00708 int scan_width; 00709 int scan_height; 00710 stg_meters_t range_max; 00711 } stg_blobfinder_config_t; 00712 00715 typedef struct 00716 { 00717 int channel; 00718 stg_color_t color; 00719 int xpos, ypos; // all values are in pixels 00720 //int width, height; 00721 int left, top, right, bottom; 00722 int area; 00723 stg_meters_t range; 00724 } stg_blobfinder_blob_t; 00725 00726 00727 // ENERGY model -------------------------------------------------------------- 00728 00730 typedef struct 00731 { 00733 stg_joules_t stored; 00734 00736 stg_bool_t charging; 00737 00739 stg_meters_t range; 00740 00742 GPtrArray* connections; 00743 } stg_energy_data_t; 00744 00746 typedef struct 00747 { 00749 stg_joules_t capacity; 00750 00752 stg_watts_t give_rate; 00753 00755 stg_watts_t take_rate; 00756 00758 stg_meters_t probe_range; 00759 00761 stg_bool_t give; 00762 00763 } stg_energy_config_t; 00764 00765 // there is currently no energy command packet 00766 00767 // BLINKENLIGHT ------------------------------------------------------- 00768 00769 //typedef struct 00770 //{ 00771 //int enable; 00772 //stg_msec_t period; 00773 //} stg_blinkenlight_t; 00774 00775 // PTZ MODEL -------------------------------------------------------- 00776 00779 typedef stg_ptz_t stg_ptz_cmd_t; 00780 00783 typedef stg_ptz_t stg_ptz_data_t; 00784 00787 typedef struct 00788 { 00789 stg_ptz_t min; 00790 stg_ptz_t max; 00791 stg_ptz_t goal; 00792 stg_ptz_t speed; 00793 } stg_ptz_config_t; 00794 00795 00796 // LASER MODEL -------------------------------------------------------- 00797 00800 typedef struct 00801 { 00802 stg_meters_t range; 00803 double reflectance; 00804 } stg_laser_sample_t; 00805 00808 typedef struct 00809 { 00810 stg_radians_t fov; 00811 stg_meters_t range_max; 00812 stg_meters_t range_min; 00813 00816 int samples; 00817 00821 int resolution; 00822 } stg_laser_config_t; 00823 00824 // GRIPPER MODEL -------------------------------------------------------- 00825 00826 typedef enum { 00827 STG_GRIPPER_PADDLE_OPEN = 0, // default state 00828 STG_GRIPPER_PADDLE_CLOSED, 00829 STG_GRIPPER_PADDLE_OPENING, 00830 STG_GRIPPER_PADDLE_CLOSING, 00831 } stg_gripper_paddle_state_t; 00832 00833 typedef enum { 00834 STG_GRIPPER_LIFT_DOWN = 0, // default state 00835 STG_GRIPPER_LIFT_UP, 00836 STG_GRIPPER_LIFT_UPPING, // verbed these to match the paddle state 00837 STG_GRIPPER_LIFT_DOWNING, 00838 } stg_gripper_lift_state_t; 00839 00840 typedef enum { 00841 STG_GRIPPER_CMD_NOP = 0, // default state 00842 STG_GRIPPER_CMD_OPEN, 00843 STG_GRIPPER_CMD_CLOSE, 00844 STG_GRIPPER_CMD_UP, 00845 STG_GRIPPER_CMD_DOWN 00846 } stg_gripper_cmd_type_t; 00847 00850 typedef struct 00851 { 00852 stg_size_t paddle_size; 00853 00854 stg_gripper_paddle_state_t paddles; 00855 stg_gripper_lift_state_t lift; 00856 00857 double paddle_position; 00858 double lift_position; 00859 00860 stg_meters_t inner_break_beam_inset; 00861 stg_meters_t outer_break_beam_inset; 00862 stg_bool_t paddles_stalled; // true iff some solid object stopped 00863 // the paddles closing or opening 00864 00865 GSList *grip_stack; 00866 int grip_stack_size; 00867 00868 double close_limit; 00869 00870 } stg_gripper_config_t; 00871 00874 typedef struct 00875 { 00876 stg_gripper_cmd_type_t cmd; 00877 int arg; 00878 } stg_gripper_cmd_t; 00879 00880 00883 typedef struct 00884 { 00885 stg_gripper_paddle_state_t paddles; 00886 stg_gripper_lift_state_t lift; 00887 00888 double paddle_position; 00889 double lift_position; 00890 00891 stg_bool_t inner_break_beam; 00892 stg_bool_t outer_break_beam; 00893 00894 stg_bool_t paddle_contacts[2]; 00895 00896 stg_bool_t paddles_stalled; // true iff some solid object stopped 00897 // the paddles closing or opening 00898 00899 int stack_count; 00900 00901 00902 } stg_gripper_data_t; 00903 00904 00905 // FIDUCIAL MODEL -------------------------------------------------------- 00906 00909 typedef struct 00910 { 00911 stg_meters_t max_range_anon; //< maximum detection range 00912 stg_meters_t max_range_id; 00913 stg_meters_t min_range; 00914 stg_radians_t fov; 00915 stg_radians_t heading; 00916 00919 char* key; 00920 } stg_fiducial_config_t; 00921 00924 typedef struct 00925 { 00926 stg_meters_t range; 00927 stg_radians_t bearing; 00928 stg_pose_t geom; 00929 int id; 00930 00931 } stg_fiducial_t; 00932 00933 // RANGER MODEL -------------------------------------------------------- 00934 00935 typedef struct 00936 { 00937 stg_pose_t pose; 00938 stg_size_t size; 00939 stg_bounds_t bounds_range; 00940 stg_radians_t fov; 00941 int ray_count; 00942 } stg_ranger_config_t; 00943 00944 typedef struct 00945 { 00946 stg_meters_t range; 00947 //double error; // TODO 00948 } stg_ranger_sample_t; 00949 00950 // BUMPER MODEL -------------------------------------------------------- 00951 00952 typedef struct 00953 { 00954 stg_pose_t pose; 00955 stg_meters_t length; 00956 } stg_bumper_config_t; 00957 00958 typedef struct 00959 { 00960 stg_model_t* hit; 00961 stg_point_t hit_point; 00962 } stg_bumper_sample_t; 00963 00964 // POSITION MODEL -------------------------------------------------------- 00965 00966 typedef enum 00967 { STG_POSITION_CONTROL_VELOCITY, STG_POSITION_CONTROL_POSITION, 00968 STG_POSITION_CONTROL_VELOCITY_HEADING } 00969 stg_position_control_mode_t; 00970 00971 #define STG_POSITION_CONTROL_DEFAULT STG_POSITION_CONTROL_VELOCITY 00972 00973 typedef enum 00974 { STG_POSITION_LOCALIZATION_GPS, STG_POSITION_LOCALIZATION_ODOM } 00975 stg_position_localization_mode_t; 00976 00977 #define STG_POSITION_LOCALIZATION_DEFAULT STG_POSITION_LOCALIZATION_GPS 00978 00980 typedef enum 00981 { STG_POSITION_DRIVE_DIFFERENTIAL, STG_POSITION_DRIVE_OMNI, STG_POSITION_DRIVE_CAR } 00982 stg_position_drive_mode_t; 00983 00984 #define STG_POSITION_DRIVE_DEFAULT STG_POSITION_DRIVE_DIFFERENTIAL 00985 00987 typedef struct 00988 { 00989 stg_meters_t x,y,a; 00990 stg_position_control_mode_t mode; 00991 } stg_position_cmd_t; 00992 00994 typedef struct 00995 { 00996 stg_pose_t pose; 00997 stg_pose_t pose_error; 00998 stg_pose_t origin; 00999 stg_velocity_t velocity; 01000 stg_velocity_t integration_error; 01001 stg_velocity_t integration_bias; 01002 //stg_bool_t stall; ///< TRUE iff the robot can't move due to a collision 01003 stg_position_localization_mode_t localization; 01004 stg_msec_t watchdog_timeout; 01005 } stg_position_data_t; 01006 01008 typedef struct 01009 { 01010 stg_position_drive_mode_t drive_mode; 01011 stg_position_localization_mode_t localization_mode; 01012 } stg_position_cfg_t; 01013 01015 void stg_model_position_set_odom( stg_model_t* mod, stg_pose_t* odom ); 01016 01017 // WIFI MODEL -------------------------------------------------------- 01018 01021 typedef struct 01022 { 01023 // Configuration for the wifi model goes here. E.g., power, range of 01024 // propagation. 01025 } stg_wifi_config_t; 01026 01029 typedef struct 01030 { 01031 // Simulated wifi data goes here. E.g., for each neighbor within 01032 // range, record the corresponding signal strength. 01033 } stg_wifi_data_t; 01034 01035 // SPEECH MODEL -------------------------------------------------------- 01036 01037 #define STG_SPEECH_MAX_STRING_LEN 256 01038 01039 typedef enum { 01040 STG_SPEECH_CMD_NOP = 0, // default state 01041 STG_SPEECH_CMD_SAY 01042 } stg_speech_cmd_type_t; 01043 01046 typedef struct 01047 { 01048 char string[STG_SPEECH_MAX_STRING_LEN]; 01049 } stg_speech_config_t; 01050 01053 typedef struct 01054 { 01055 char string[STG_SPEECH_MAX_STRING_LEN]; 01056 } stg_speech_data_t; 01057 01060 typedef struct 01061 { 01062 stg_speech_cmd_type_t cmd; 01063 char string[STG_SPEECH_MAX_STRING_LEN]; 01064 } stg_speech_cmd_t; 01065 01066 // end the group of all models 01071 // MACROS ------------------------------------------------------ 01072 // Some useful macros 01073 01084 stg_color_t stg_lookup_color(const char *name); 01085 01088 void stg_pose_sum( stg_pose_t* result, stg_pose_t* p1, stg_pose_t* p2 ); 01089 01090 // PRETTY PRINTING ------------------------------------------------- 01091 01093 void stg_print_err( const char* err ); 01095 void stg_print_geom( stg_geom_t* geom ); 01097 void stg_print_pose( stg_pose_t* pose ); 01099 void stg_print_velocity( stg_velocity_t* vel ); 01101 void stg_print_gripper_config( stg_gripper_config_t* slc ); 01103 void stg_print_laser_config( stg_laser_config_t* slc ); 01104 01105 01106 01107 // Error macros - output goes to stderr 01108 #define PRINT_ERR(m) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", __FILE__, __FUNCTION__) 01109 #define PRINT_ERR1(m,a) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, __FILE__, __FUNCTION__) 01110 #define PRINT_ERR2(m,a,b) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__) 01111 #define PRINT_ERR3(m,a,b,c) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__) 01112 #define PRINT_ERR4(m,a,b,c,d) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__) 01113 #define PRINT_ERR5(m,a,b,c,d,e) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, d, e, __FILE__, __FUNCTION__) 01114 01115 // Warning macros 01116 #define PRINT_WARN(m) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", __FILE__, __FUNCTION__) 01117 #define PRINT_WARN1(m,a) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, __FILE__, __FUNCTION__) 01118 #define PRINT_WARN2(m,a,b) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__) 01119 #define PRINT_WARN3(m,a,b,c) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__) 01120 #define PRINT_WARN4(m,a,b,c,d) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__) 01121 #define PRINT_WARN5(m,a,b,c,d,e) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, d, e, __FILE__, __FUNCTION__) 01122 01123 // Message macros 01124 #ifdef DEBUG 01125 #define PRINT_MSG(m) printf( "Stage: "m" (%s %s)\n", __FILE__, __FUNCTION__) 01126 #define PRINT_MSG1(m,a) printf( "Stage: "m" (%s %s)\n", a, __FILE__, __FUNCTION__) 01127 #define PRINT_MSG2(m,a,b) printf( "Stage: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__) 01128 #define PRINT_MSG3(m,a,b,c) printf( "Stage: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__) 01129 #define PRINT_MSG4(m,a,b,c,d) printf( "Stage: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__) 01130 #define PRINT_MSG5(m,a,b,c,d,e) printf( "Stage: "m" (%s %s)\n", a, b, c, d, e,__FILE__, __FUNCTION__) 01131 #else 01132 #define PRINT_MSG(m) printf( "Stage: "m"\n" ) 01133 #define PRINT_MSG1(m,a) printf( "Stage: "m"\n", a) 01134 #define PRINT_MSG2(m,a,b) printf( "Stage: "m"\n,", a, b ) 01135 #define PRINT_MSG3(m,a,b,c) printf( "Stage: "m"\n", a, b, c ) 01136 #define PRINT_MSG4(m,a,b,c,d) printf( "Stage: "m"\n", a, b, c, d ) 01137 #define PRINT_MSG5(m,a,b,c,d,e) printf( "Stage: "m"\n", a, b, c, d, e ) 01138 #endif 01139 01140 // DEBUG macros 01141 #ifdef DEBUG 01142 #define PRINT_DEBUG(m) printf( "debug: "m" (%s %s)\n", __FILE__, __FUNCTION__) 01143 #define PRINT_DEBUG1(m,a) printf( "debug: "m" (%s %s)\n", a, __FILE__, __FUNCTION__) 01144 #define PRINT_DEBUG2(m,a,b) printf( "debug: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__) 01145 #define PRINT_DEBUG3(m,a,b,c) printf( "debug: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__) 01146 #define PRINT_DEBUG4(m,a,b,c,d) printf( "debug: "m" (%s %s)\n", a, b, c ,d, __FILE__, __FUNCTION__) 01147 #define PRINT_DEBUG5(m,a,b,c,d,e) printf( "debug: "m" (%s %s)\n", a, b, c ,d, e, __FILE__, __FUNCTION__) 01148 #else 01149 #define PRINT_DEBUG(m) 01150 #define PRINT_DEBUG1(m,a) 01151 #define PRINT_DEBUG2(m,a,b) 01152 #define PRINT_DEBUG3(m,a,b,c) 01153 #define PRINT_DEBUG4(m,a,b,c,d) 01154 #define PRINT_DEBUG5(m,a,b,c,d,e) 01155 #endif 01156 01157 01173 #define PRECISION 100000.0 01174 01176 #define EQ(A,B) ((lrint(A*PRECISION))==(lrint(B*PRECISION))) 01177 01179 #define LT(A,B) ((lrint(A*PRECISION))<(lrint(B*PRECISION))) 01180 01182 #define GT(A,B) ((lrint(A*PRECISION))>(lrint(B*PRECISION))) 01183 01185 #define GTE(A,B) ((lrint(A*PRECISION))>=(lrint(B*PRECISION))) 01186 01188 #define LTE(A,B) ((lrint(A*PRECISION))<=(lrint(B*PRECISION))) 01189 01190 01191 01194 #ifndef TRUE 01195 #define TRUE 1 01196 #endif 01197 01198 #ifndef FALSE 01199 #define FALSE 0 01200 #endif 01201 01202 #define MILLION 1e6 01203 #define BILLION 1e9 01204 01205 #ifndef M_PI 01206 #define M_PI 3.14159265358979323846 01207 #endif 01208 01209 #ifndef TWOPI 01210 #define TWOPI (2.0*M_PI) 01211 #endif 01212 01213 #ifndef RTOD 01214 01215 #define RTOD(r) ((r) * 180.0 / M_PI) 01216 #endif 01217 01218 #ifndef DTOR 01219 01220 #define DTOR(d) ((d) * M_PI / 180.0) 01221 #endif 01222 01223 #ifndef NORMALIZE 01224 01225 #define NORMALIZE(z) atan2(sin(z), cos(z)) 01226 #endif 01227 01228 // end doc group libstage_utilities 01231 #ifdef __cplusplus 01232 } 01233 #endif 01234 01235 // end documentation group libstage 01238 #endif
Generated on Thu Dec 13 14:35:18 2007 for Stage by 1.4.6