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


p2os_driver
Author(s): Hunter L. Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Wed Mar 27 2019 02:34:57