Classes | Defines | Enumerations | Functions | Variables
robot_params.h File Reference
#include <string>
Include dependency graph for robot_params.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  bumper_def_t
struct  RobotParams_t
struct  sonar_pose_t

Defines

#define ARGINT   0x3B
#define ARGNINT   0x1B
#define ARGSTR   0x2B
#define ARMINFOPAC   161
#define ARMPAC   160
#define CMUCAM_IMAGE_HEIGHT   143
#define CMUCAM_IMAGE_WIDTH   80
#define CMUCAM_MESSAGE_LEN   10
#define DEFAULT_P2OS_PORT   "/dev/ttyS0"
#define DEFAULT_P2OS_TCP_REMOTE_HOST   "localhost"
#define DEFAULT_P2OS_TCP_REMOTE_PORT   8101
#define DTOR(a)   M_PI * a / 180.0
#define ENCODER   0x90
#define GRIPclose   2
#define GRIPdeploy   8
#define GRIPhalt   15
#define GRIPopen   1
#define GRIPpress   16
#define GRIPstop   3
#define GRIPstore   7
#define GYROPAC   0x98
#define LIFTcarry   17
#define LIFTdown   5
#define LIFTstop   6
#define LIFTup   4
#define MOTOR_DEF_MAX_SPEED   0.5
#define MOTOR_DEF_MAX_TURNSPEED   DTOR(100)
#define P2OS_CYCLETIME_USEC   200000
#define P2OS_NOMINAL_VOLTAGE   12.0
#define PLAYER_NUM_ROBOT_TYPES   30
#define RTOD(a)   180.0 * a / M_PI
#define SERAUX   0xB0
#define SERAUX2   0xB8
#define STATUSMOVING   0x33
#define STATUSSTOPPED   0x32
#define SYNC0   0
#define SYNC1   1
#define SYNC2   2

Enumerations

enum  P2OSCommand {
  PULSE = 0, OPEN = 1, CLOSE = 2, ENABLE = 4,
  SETA = 5, SETV = 6, SETO = 7, MOVE = 8,
  ROTATE = 9, SETRV = 10, VEL = 11, HEAD = 12,
  DHEAD = 13, SAY = 15, JOYINFO = 17, CONFIG = 18,
  ENCODER = 19, RVEL = 21, DCHEAD = 22, SETRA = 23,
  SONAR = 28, STOP = 29, DIGOUT = 30, VEL2 = 32,
  GRIPPER = 33, ADSEL = 35, GRIPPERVAL = 36, GRIPPERPACREQUEST = 37,
  IOREQUEST = 40, PTUPOS = 41, TTY2 = 42, GETAUX = 43,
  BUMP_STALL = 44, TCM2 = 45, JOYDRIVE = 47, MOVINGBLINK = 49,
  HOSTBAUD = 50, AUX1BAUD = 51, AUX2BAUD = 52, ESTOP = 55,
  ESTALL = 56, GYRO = 58, CALCOMP = 65, TTY3 = 66,
  GETAUX2 = 67, ARM_INFO = 70, ARM_STATUS = 71, ARM_INIT = 72,
  ARM_CHECK = 73, ARM_POWER = 74, ARM_HOME = 75, ARM_PARK = 76,
  ARM_POS = 77, ARM_SPEED = 78, ARM_STOP = 79, ARM_AUTOPARK = 80,
  ARM_GRIPPARK = 81, ROTKP = 82, ROTKV = 83, ROTKI = 84,
  TRANSKP = 85, TRANSKV = 86, TRANSKI = 87, SOUND = 90,
  PLAYLIST = 91, SOUNDTOG = 92, POWER_PC = 95, POWER_LRF = 96,
  POWER_5V = 97, POWER_12V = 98, POWER_24V = 98, POWER_AUX_PC = 125,
  POWER_TOUCHSCREEN = 126, POWER_PTZ = 127, POWER_AUDIO = 128, POWER_LRF2 = 129,
  LATVEL = 110, LATACCEL = 113, SETLATV = 0
}

Functions

void initialize_robot_params (void)

Variables

RobotParams_t PlayerRobotParams []

Define Documentation

#define ARGINT   0x3B

Definition at line 203 of file robot_params.h.

#define ARGNINT   0x1B

Definition at line 204 of file robot_params.h.

#define ARGSTR   0x2B

Definition at line 205 of file robot_params.h.

#define ARMINFOPAC   161

Definition at line 199 of file robot_params.h.

#define ARMPAC   160

Definition at line 198 of file robot_params.h.

#define CMUCAM_IMAGE_HEIGHT   143

Definition at line 222 of file robot_params.h.

#define CMUCAM_IMAGE_WIDTH   80

Definition at line 221 of file robot_params.h.

#define CMUCAM_MESSAGE_LEN   10

Definition at line 223 of file robot_params.h.

#define DEFAULT_P2OS_PORT   "/dev/ttyS0"

Definition at line 226 of file robot_params.h.

#define DEFAULT_P2OS_TCP_REMOTE_HOST   "localhost"

Definition at line 227 of file robot_params.h.

#define DEFAULT_P2OS_TCP_REMOTE_PORT   8101

Definition at line 228 of file robot_params.h.

#define DTOR (   a)    M_PI * a / 180.0

Definition at line 231 of file robot_params.h.

#define ENCODER   0x90

Definition at line 194 of file robot_params.h.

#define GRIPclose   2

Definition at line 209 of file robot_params.h.

#define GRIPdeploy   8

Definition at line 215 of file robot_params.h.

#define GRIPhalt   15

Definition at line 216 of file robot_params.h.

#define GRIPopen   1

Definition at line 208 of file robot_params.h.

#define GRIPpress   16

Definition at line 217 of file robot_params.h.

#define GRIPstop   3

Definition at line 210 of file robot_params.h.

#define GRIPstore   7

Definition at line 214 of file robot_params.h.

#define GYROPAC   0x98

Definition at line 197 of file robot_params.h.

#define LIFTcarry   17

Definition at line 218 of file robot_params.h.

#define LIFTdown   5

Definition at line 212 of file robot_params.h.

#define LIFTstop   6

Definition at line 213 of file robot_params.h.

#define LIFTup   4

Definition at line 211 of file robot_params.h.

#define MOTOR_DEF_MAX_SPEED   0.5

Definition at line 71 of file robot_params.h.

#define MOTOR_DEF_MAX_TURNSPEED   DTOR(100)

Definition at line 72 of file robot_params.h.

#define P2OS_CYCLETIME_USEC   200000

Definition at line 79 of file robot_params.h.

#define P2OS_NOMINAL_VOLTAGE   12.0

Definition at line 83 of file robot_params.h.

#define PLAYER_NUM_ROBOT_TYPES   30

Definition at line 68 of file robot_params.h.

#define RTOD (   a)    180.0 * a / M_PI

Definition at line 232 of file robot_params.h.

#define SERAUX   0xB0

Definition at line 195 of file robot_params.h.

#define SERAUX2   0xB8

Definition at line 196 of file robot_params.h.

#define STATUSMOVING   0x33

Definition at line 193 of file robot_params.h.

#define STATUSSTOPPED   0x32

Definition at line 192 of file robot_params.h.

#define SYNC0   0

Definition at line 86 of file robot_params.h.

#define SYNC1   1

Definition at line 87 of file robot_params.h.

#define SYNC2   2

Definition at line 88 of file robot_params.h.


Enumeration Type Documentation

Enumerator:
PULSE 
OPEN 
CLOSE 
ENABLE 
SETA 
SETV 
SETO 
MOVE 

int, translational move (mm)

ROTATE 

int, set rotational velocity, duplicate of RVEL (deg/sec)

SETRV 

int, sets the maximum rotational velocity (deg/sec)

VEL 
HEAD 

int, turn to absolute heading 0-359 (degrees)

DHEAD 

int, turn relative to current heading (degrees)

SAY 

string, makes the robot beep. up to 20 pairs of duration (20 ms incrs) and tones (halfcycle)

JOYINFO 
CONFIG 

int, request configuration packet

ENCODER 

int, > 0 to request continous stream of packets, 0 to stop

RVEL 
DCHEAD 

int, colbert relative heading setpoint (degrees)

SETRA 
SONAR 
STOP 
DIGOUT 

int, sets the digout lines

VEL2 
GRIPPER 
ADSEL 

int, select the port given as argument

GRIPPERVAL 
GRIPPERPACREQUEST 

p2 gripper packet request

IOREQUEST 

request iopackets from p2os

PTUPOS 

most-sig byte is port number, least-sig byte is pulse width

TTY2 
GETAUX 
BUMP_STALL 
TCM2 

TCM2 module commands, see tcm2 manual for details.

JOYDRIVE 
MOVINGBLINK 

int, 1 to blink lamp quickly before moving, 0 not to (for patrolbot)

HOSTBAUD 

int, set baud rate for host port - 0=9600, 1=19200, 2=38400, 3=57600, 4=115200

AUX1BAUD 

int, set baud rate for Aux1 - 0=9600, 1=19200, 2=38400, 3=57600, 4=115200

AUX2BAUD 

int, set baud rate for Aux2 - 0=9600, 1=19200, 2=38400, 3=57600, 4=115200

ESTOP 

none, emergency stop, overrides decel

ESTALL 
GYRO 
CALCOMP 

int, commands for calibrating compass, see compass manual

TTY3 
GETAUX2 
ARM_INFO 
ARM_STATUS 
ARM_INIT 
ARM_CHECK 
ARM_POWER 
ARM_HOME 
ARM_PARK 
ARM_POS 
ARM_SPEED 
ARM_STOP 
ARM_AUTOPARK 
ARM_GRIPPARK 
ROTKP 
ROTKV 
ROTKI 
TRANSKP 
TRANSKV 
TRANSKI 
SOUND 
PLAYLIST 
SOUNDTOG 

int, AmigoBot (old H8 model) specific, enable(1) or diable(0) sound

POWER_PC 
POWER_LRF 
POWER_5V 
POWER_12V 
POWER_24V 
POWER_AUX_PC 
POWER_TOUCHSCREEN 
POWER_PTZ 
POWER_AUDIO 
POWER_LRF2 
LATVEL 

int, sets the lateral velocity (mm)

LATACCEL 

int, sets the lateral acceleration (+, mm/sec2) or lateral deceleration (-, mm/sec2)

SETLATV 

int, someday will set the vel

Definition at line 90 of file robot_params.h.


Function Documentation

void initialize_robot_params ( void  )

Definition at line 2122 of file robot_params.cc.


Variable Documentation

Definition at line 2119 of file robot_params.cc.



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 Aug 5 2017 02:20:17