$search
00001 /* 00002 * P2OS for ROS 00003 * Copyright (C) 2009 00004 * David Feil-Seifer, Brian Gerkey, Kasper Stoy, 00005 * Richard Vaughan, & Andrew Howard 00006 * 00007 * 00008 * This program is free software; you can redistribute it and/or modify 00009 * it under the terms of the GNU General Public License as published by 00010 * the Free Software Foundation; either version 2 of the License, or 00011 * (at your option) any later version. 00012 * 00013 * This program is distributed in the hope that it will be useful, 00014 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00015 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00016 * GNU General Public License for more details. 00017 * 00018 * You should have received a copy of the GNU General Public License 00019 * along with this program; if not, write to the Free Software 00020 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00021 * 00022 */ 00023 00024 /* 00025 * robot_params.h 00026 * 00027 * ActivMedia robot parameters, automatically generated by saphconv.tcl from 00028 * Saphira parameter files: 00029 * amigo.p 00030 * amigo-sh.p 00031 * p2at.p 00032 * p2at8+.p 00033 * p2at8.p 00034 * p2ce.p 00035 * p2d8+.p 00036 * p2d8.p 00037 * p2de.p 00038 * p2df.p 00039 * p2dx.p 00040 * p2it.p 00041 * p2pb.p 00042 * p2pp.p 00043 * p3at-sh.p 00044 * p3at.p 00045 * p3atiw.p 00046 * p3dx-sh.p 00047 * p3dx.p 00048 * peoplebot-sh.p 00049 * perfpb+.p 00050 * perfpb.p 00051 * pion1m.p 00052 * pion1x.p 00053 * pionat.p 00054 * powerbot-sh.p 00055 * powerbot.p 00056 * psos1m.p 00057 * psos1x.p 00058 */ 00059 00060 #ifndef _ROBOT_PARAMS_H 00061 #define _ROBOT_PARAMS_H 00062 #include <string> 00063 00064 void initialize_robot_params(void); 00065 00066 00067 #define PLAYER_NUM_ROBOT_TYPES 29 00068 00069 // Default max speeds 00070 #define MOTOR_DEF_MAX_SPEED 0.5 00071 #define MOTOR_DEF_MAX_TURNSPEED DTOR(100) 00072 00073 /* 00074 * Apparently, newer kernel require a large value (200000) here. It only 00075 * makes the initialization phase take a bit longer, and doesn't have any 00076 * impact on the speed at which packets are received from P2OS 00077 */ 00078 #define P2OS_CYCLETIME_USEC 200000 00079 00080 /* p2os constants */ 00081 00082 #define P2OS_NOMINAL_VOLTAGE 12.0 00083 00084 /* Command numbers */ 00085 #define SYNC0 0 00086 #define SYNC1 1 00087 #define SYNC2 2 00088 00089 enum P2OSCommand { 00090 PULSE = 0, 00091 OPEN = 1, 00092 CLOSE = 2, 00093 ENABLE = 4, 00094 SETA = 5, 00095 SETV = 6, 00096 SETO = 7, 00097 MOVE = 8, 00098 ROTATE = 9, 00099 SETRV = 10, 00100 VEL = 11, 00101 HEAD = 12, 00102 DHEAD = 13, 00103 //DROTATE = 14, does not really exist 00104 SAY = 15, 00106 JOYINFO = 17, // int, requests joystick packet, 0 to stop, 1 for 1, 2 for 00107 // continuous 00108 CONFIG = 18, 00109 ENCODER = 19, 00110 RVEL = 21, 00111 DCHEAD = 22, 00112 SETRA = 23, 00113 SONAR = 28, 00114 STOP = 29, 00115 DIGOUT = 30, 00116 //TIMER = 31, ... no clue about this one 00117 VEL2 = 32, 00118 GRIPPER = 33, 00119 //KICK = 34, um... 00120 ADSEL = 35, 00121 GRIPPERVAL = 36, 00122 GRIPPERPACREQUEST = 37, 00123 IOREQUEST = 40, 00124 PTUPOS = 41, 00125 TTY2 = 42, // Added in AmigOS 1.2 00126 GETAUX = 43, // Added in AmigOS 1.2 00127 BUMP_STALL = 44, 00128 TCM2 = 45, 00129 JOYDRIVE = 47, 00130 MOVINGBLINK = 49, 00131 00132 HOSTBAUD = 50, 00133 00134 AUX1BAUD = 51, 00135 00136 AUX2BAUD = 52, 00137 00138 ESTOP = 55, 00139 ESTALL = 56, // ? 00140 GYRO = 58, // Added in AROS 1.8 00141 // SRISIM specific: 00142 00143 // for calibrating the compass: 00144 CALCOMP = 65, 00145 00146 TTY3 = 66, // Added in AmigOS 1.3 00147 GETAUX2 = 67, // Added in AmigOS 1.3 00148 ARM_INFO = 70, 00149 ARM_STATUS = 71, 00150 ARM_INIT = 72, 00151 ARM_CHECK = 73, 00152 ARM_POWER = 74, 00153 ARM_HOME = 75, 00154 ARM_PARK = 76, 00155 ARM_POS = 77, 00156 ARM_SPEED = 78, 00157 ARM_STOP = 79, 00158 ARM_AUTOPARK = 80, 00159 ARM_GRIPPARK = 81, 00160 00161 ROTKP = 82, // Added in P2OS1.M 00162 ROTKV = 83, // Added in P2OS1.M 00163 ROTKI = 84, // Added in P2OS1.M 00164 TRANSKP = 85, // Added in P2OS1.M 00165 TRANSKV = 86, // Added in P2OS1.M 00166 TRANSKI = 87, // Added in P2OS1.M 00167 SOUND = 90, 00168 PLAYLIST = 91, 00169 SOUNDTOG = 92, 00170 00171 // Power commands 00172 POWER_PC = 95, 00173 POWER_LRF = 96, 00174 POWER_5V = 97, 00175 POWER_12V = 98, 00176 POWER_24V = 98, 00177 POWER_AUX_PC = 125, 00178 POWER_TOUCHSCREEN = 126, 00179 POWER_PTZ = 127, 00180 POWER_AUDIO = 128, 00181 POWER_LRF2 = 129, 00182 00183 // For SEEKUR or later lateral-capable robots 00184 LATVEL = 110, 00185 LATACCEL = 113, 00186 00187 SETLATV = 0, 00188 }; 00189 00190 /* Server Information Packet (SIP) types */ 00191 #define STATUSSTOPPED 0x32 00192 #define STATUSMOVING 0x33 00193 #define ENCODER 0x90 00194 #define SERAUX 0xB0 00195 #define SERAUX2 0xB8 // Added in AmigOS 1.3 00196 #define GYROPAC 0x98 // Added AROS 1.8 00197 #define ARMPAC 160 // ARMpac 00198 #define ARMINFOPAC 161 // ARMINFOpac 00199 //#define PLAYLIST 0xD0 00200 00201 /* Argument types */ 00202 #define ARGINT 0x3B // Positive int (LSB, MSB) 00203 #define ARGNINT 0x1B // Negative int (LSB, MSB) 00204 #define ARGSTR 0x2B // String (Note: 1st byte is length!!) 00205 00206 /* gripper stuff */ 00207 #define GRIPopen 1 00208 #define GRIPclose 2 00209 #define GRIPstop 3 00210 #define LIFTup 4 00211 #define LIFTdown 5 00212 #define LIFTstop 6 00213 #define GRIPstore 7 00214 #define GRIPdeploy 8 00215 #define GRIPhalt 15 00216 #define GRIPpress 16 00217 #define LIFTcarry 17 00218 00219 /* CMUcam stuff */ 00220 #define CMUCAM_IMAGE_WIDTH 80 00221 #define CMUCAM_IMAGE_HEIGHT 143 00222 #define CMUCAM_MESSAGE_LEN 10 00223 00224 /* conection stuff */ 00225 #define DEFAULT_P2OS_PORT "/dev/ttyS0" 00226 #define DEFAULT_P2OS_TCP_REMOTE_HOST "localhost" 00227 #define DEFAULT_P2OS_TCP_REMOTE_PORT 8101 00228 00229 /* degrees and radians */ 00230 #define DTOR(a) M_PI * a / 180.0 00231 #define RTOD(a) 180.0 * a / M_PI 00232 00233 typedef struct 00234 { 00235 double x; 00236 double y; 00237 double th; 00238 double length; 00239 double radius; 00240 } bumper_def_t; 00241 00242 typedef struct 00243 { 00244 double x; 00245 double y; 00246 double th; 00247 } sonar_pose_t; 00248 00249 00250 typedef struct 00251 { 00252 double AngleConvFactor; // 00253 std::string Class; 00254 double DiffConvFactor; // 00255 double DistConvFactor; // 00256 int FrontBumpers; // 00257 double GyroScaler; // 00258 int HasMoveCommand; // 00259 int Holonomic; // 00260 int IRNum; // 00261 int IRUnit; // 00262 int LaserFlipped; // 00263 std::string LaserIgnore; 00264 std::string LaserPort; 00265 int LaserPossessed; // 00266 int LaserPowerControlled; // 00267 int LaserTh; // 00268 int LaserX; // 00269 int LaserY; // 00270 int MaxRVelocity; // 00271 int MaxVelocity; // 00272 int NewTableSensingIR; // 00273 int NumFrontBumpers; // 00274 int NumRearBumpers; // 00275 double RangeConvFactor; // 00276 int RearBumpers; // 00277 int RequestEncoderPackets; // 00278 int RequestIOPackets; // 00279 int RobotDiagonal; // 00280 int RobotLength; // 00281 int RobotRadius; // 00282 int RobotWidth; // 00283 int RotAccel; // 00284 int RotDecel; // 00285 int RotVelMax; // 00286 int SettableAccsDecs; // 00287 int SettableVelMaxes; // 00288 int SonarNum; // 00289 std::string Subclass; 00290 int SwitchToBaudRate; // 00291 int TableSensingIR; // 00292 int TransAccel; // 00293 int TransDecel; // 00294 int TransVelMax; // 00295 int Vel2Divisor; // 00296 double VelConvFactor; // 00297 sonar_pose_t sonar_pose[32]; 00298 //bumper_def_t bumper_geom[32]; 00299 } RobotParams_t; 00300 00301 00302 extern RobotParams_t PlayerRobotParams[]; 00303 00304 00305 #endif