robot_params.h
Go to the documentation of this file.
1 /*
2  * P2OS for ROS
3  * Copyright (C) 2009
4  * David Feil-Seifer, Brian Gerkey, Kasper Stoy,
5  * Richard Vaughan, & Andrew Howard
6  *
7  *
8  * This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program; if not, write to the Free Software
20  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
21  *
22  */
23 
24 /*
25  * robot_params.h
26  *
27  * ActivMedia robot parameters, automatically generated by saphconv.tcl from
28  * Saphira parameter files:
29  * amigo.p
30  * amigo-sh.p
31  * p2at.p
32  * p2at8+.p
33  * p2at8.p
34  * p2ce.p
35  * p2d8+.p
36  * p2d8.p
37  * p2de.p
38  * p2df.p
39  * p2dx.p
40  * p2it.p
41  * p2pb.p
42  * p2pp.p
43  * p3at-sh.p
44  * p3at.p
45  * p3atiw.p
46  * p3dx-sh.p
47  * p3dx.p
48  * peoplebot-sh.p
49  * perfpb+.p
50  * perfpb.p
51  * pion1m.p
52  * pion1x.p
53  * pionat.p
54  * powerbot-sh.p
55  * powerbot.p
56  * psos1m.p
57  * psos1x.p
58 */
59 
60 #ifndef _ROBOT_PARAMS_H
61 #define _ROBOT_PARAMS_H
62 #include <string>
63 
64 void initialize_robot_params(void);
65 
66 
67 #define PLAYER_NUM_ROBOT_TYPES 29
68 
69 // Default max speeds
70 #define MOTOR_DEF_MAX_SPEED 0.5
71 #define MOTOR_DEF_MAX_TURNSPEED DTOR(100)
72 
73 /*
74  * Apparently, newer kernel require a large value (200000) here. It only
75  * makes the initialization phase take a bit longer, and doesn't have any
76  * impact on the speed at which packets are received from P2OS
77  */
78 #define P2OS_CYCLETIME_USEC 200000
79 
80 /* p2os constants */
81 
82 #define P2OS_NOMINAL_VOLTAGE 12.0
83 
84 /* Command numbers */
85 #define SYNC0 0
86 #define SYNC1 1
87 #define SYNC2 2
88 
90  PULSE = 0,
91  OPEN = 1,
92  CLOSE = 2,
93  ENABLE = 4,
94  SETA = 5,
95  SETV = 6,
96  SETO = 7,
97  MOVE = 8,
98  ROTATE = 9,
99  SETRV = 10,
100  VEL = 11,
101  HEAD = 12,
102  DHEAD = 13,
103  //DROTATE = 14, does not really exist
104  SAY = 15,
106  JOYINFO = 17, // int, requests joystick packet, 0 to stop, 1 for 1, 2 for
107  // continuous
108  CONFIG = 18,
109  ENCODER = 19,
110  RVEL = 21,
111  DCHEAD = 22,
112  SETRA = 23,
113  SONAR = 28,
114  STOP = 29,
115  DIGOUT = 30,
116  //TIMER = 31, ... no clue about this one
117  VEL2 = 32,
118  GRIPPER = 33,
119  //KICK = 34, um...
120  ADSEL = 35,
123  IOREQUEST = 40,
124  PTUPOS = 41,
125  TTY2 = 42, // Added in AmigOS 1.2
126  GETAUX = 43, // Added in AmigOS 1.2
128  TCM2 = 45,
129  JOYDRIVE = 47,
130  MOVINGBLINK = 49,
131  HOSTBAUD = 50,
133  AUX1BAUD = 51,
135  AUX2BAUD = 52,
137  ESTOP = 55,
139  ESTALL = 56, // ?
140  GYRO = 58, // Added in AROS 1.8
141  // SRISIM specific:
142 
143  // for calibrating the compass:
144  CALCOMP = 65,
145 
146  TTY3 = 66, // Added in AmigOS 1.3
147  GETAUX2 = 67, // Added in AmigOS 1.3
148  ARM_INFO = 70,
150  ARM_INIT = 72,
151  ARM_CHECK = 73,
152  ARM_POWER = 74,
153  ARM_HOME = 75,
154  ARM_PARK = 76,
155  ARM_POS = 77,
156  ARM_SPEED = 78,
157  ARM_STOP = 79,
160 
161  ROTKP = 82, // Added in P2OS1.M
162  ROTKV = 83, // Added in P2OS1.M
163  ROTKI = 84, // Added in P2OS1.M
164  TRANSKP = 85, // Added in P2OS1.M
165  TRANSKV = 86, // Added in P2OS1.M
166  TRANSKI = 87, // Added in P2OS1.M
167  SOUND = 90,
168  PLAYLIST = 91,
169  SOUNDTOG = 92,
170  // Power commands
172  POWER_PC = 95,
173  POWER_LRF = 96,
174  POWER_5V = 97,
175  POWER_12V = 98,
176  POWER_24V = 98,
179  POWER_PTZ = 127,
180  POWER_AUDIO = 128,
181  POWER_LRF2 = 129,
182 
183  // For SEEKUR or later lateral-capable robots
184  LATVEL = 110,
185  LATACCEL = 113,
186  SETLATV = 0,
188 };
189 
190 /* Server Information Packet (SIP) types */
191 #define STATUSSTOPPED 0x32
192 #define STATUSMOVING 0x33
193 #define ENCODER 0x90
194 #define SERAUX 0xB0
195 #define SERAUX2 0xB8 // Added in AmigOS 1.3
196 #define GYROPAC 0x98 // Added AROS 1.8
197 #define ARMPAC 160 // ARMpac
198 #define ARMINFOPAC 161 // ARMINFOpac
199 //#define PLAYLIST 0xD0
200 
201 /* Argument types */
202 #define ARGINT 0x3B // Positive int (LSB, MSB)
203 #define ARGNINT 0x1B // Negative int (LSB, MSB)
204 #define ARGSTR 0x2B // String (Note: 1st byte is length!!)
205 
206 /* gripper stuff */
207 #define GRIPopen 1
208 #define GRIPclose 2
209 #define GRIPstop 3
210 #define LIFTup 4
211 #define LIFTdown 5
212 #define LIFTstop 6
213 #define GRIPstore 7
214 #define GRIPdeploy 8
215 #define GRIPhalt 15
216 #define GRIPpress 16
217 #define LIFTcarry 17
218 
219 /* CMUcam stuff */
220 #define CMUCAM_IMAGE_WIDTH 80
221 #define CMUCAM_IMAGE_HEIGHT 143
222 #define CMUCAM_MESSAGE_LEN 10
223 
224 /* conection stuff */
225 #define DEFAULT_P2OS_PORT "/dev/ttyS0"
226 #define DEFAULT_P2OS_TCP_REMOTE_HOST "localhost"
227 #define DEFAULT_P2OS_TCP_REMOTE_PORT 8101
228 
229 /* degrees and radians */
230 #define DTOR(a) M_PI * a / 180.0
231 #define RTOD(a) 180.0 * a / M_PI
232 
233 typedef struct
234 {
235  double x;
236  double y;
237  double th;
238  double length;
239  double radius;
240 } bumper_def_t;
241 
242 typedef struct
243 {
244  double x;
245  double y;
246  double th;
247 } sonar_pose_t;
248 
249 
250 typedef struct
251 {
252  double AngleConvFactor; //
253  std::string Class;
254  double DiffConvFactor; //
255  double DistConvFactor; //
256  int FrontBumpers; //
257  double GyroScaler; //
259  int Holonomic; //
260  int IRNum; //
261  int IRUnit; //
262  int LaserFlipped; //
263  std::string LaserIgnore;
264  std::string LaserPort;
267  int LaserTh; //
268  int LaserX; //
269  int LaserY; //
270  int MaxRVelocity; //
271  int MaxVelocity; //
275  double RangeConvFactor; //
276  int RearBumpers; //
280  int RobotLength; //
281  int RobotRadius; //
282  int RobotWidth; //
283  int RotAccel; //
284  int RotDecel; //
285  int RotVelMax; //
288  int SonarNum; //
289  std::string Subclass;
292  int TransAccel; //
293  int TransDecel; //
294  int TransVelMax; //
295  int Vel2Divisor; //
296  double VelConvFactor; //
297  sonar_pose_t sonar_pose[32];
298  //bumper_def_t bumper_geom[32];
299 } RobotParams_t;
300 
301 
303 
304 
305 #endif
most-sig byte is port number, least-sig byte is pulse width
Definition: robot_params.h:124
request iopackets from p2os
Definition: robot_params.h:123
int, set rotational velocity, duplicate of RVEL (deg/sec)
Definition: robot_params.h:98
std::string Class
Definition: robot_params.h:253
double AngleConvFactor
Definition: robot_params.h:252
int, translational move (mm)
Definition: robot_params.h:97
int, turn relative to current heading (degrees)
Definition: robot_params.h:102
int, someday will set the vel
Definition: robot_params.h:187
int, turn to absolute heading 0-359 (degrees)
Definition: robot_params.h:101
P2OSCommand
Definition: robot_params.h:89
#define ENCODER
Definition: robot_params.h:193
std::string LaserIgnore
Definition: robot_params.h:263
int RequestEncoderPackets
Definition: robot_params.h:277
RobotParams_t PlayerRobotParams[]
int, request configuration packet
Definition: robot_params.h:108
int, sets the maximum rotational velocity (deg/sec)
Definition: robot_params.h:99
p2 gripper packet request
Definition: robot_params.h:122
int, commands for calibrating compass, see compass manual
Definition: robot_params.h:144
double RangeConvFactor
Definition: robot_params.h:275
std::string Subclass
Definition: robot_params.h:289
double VelConvFactor
Definition: robot_params.h:296
none, emergency stop, overrides decel
Definition: robot_params.h:138
std::string LaserPort
Definition: robot_params.h:264
int, sets the lateral velocity (mm)
Definition: robot_params.h:184
int LaserPowerControlled
Definition: robot_params.h:266
TCM2 module commands, see tcm2 manual for details.
Definition: robot_params.h:128
double GyroScaler
Definition: robot_params.h:257
void initialize_robot_params(void)
int, select the port given as argument
Definition: robot_params.h:120
double DistConvFactor
Definition: robot_params.h:255
int, colbert relative heading setpoint (degrees)
Definition: robot_params.h:111
int, sets the digout lines
Definition: robot_params.h:115
double DiffConvFactor
Definition: robot_params.h:254


p2os_driver
Author(s): Hunter Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Wed Jun 25 2014 09:37:15