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


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 Sat Jun 20 2020 03:29:42