Home
FAQ
Player
Stage
Gazebo
Contrib
Documentation
Publications
Contributors
Users

Project
Download
Bugs/Feedback
Mailing lists

Radish

Old news
Old stuff

p2os.h

Go to the documentation of this file.
00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000  
00004  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00005  *                      
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 
00023 /*
00024  * $Id: p2os.h,v 1.17 2005/01/26 18:48:31 gerkey Exp $
00025  *
00026  *   the P2OS device.  it's the parent device for all the P2 'sub-devices',
00027  *   like gripper, position, sonar, etc.  there's a thread here that
00028  *   actually interacts with P2OS via the serial line.  the other
00029  *   "devices" communicate with this thread by putting into and getting
00030  *   data out of shared buffers.
00031  */
00032 #ifndef _P2OSDEVICE_H
00033 #define _P2OSDEVICE_H
00034 
00035 #include <pthread.h>
00036 #include <sys/time.h>
00037 
00038 #include <driver.h>
00039 #include <drivertable.h>
00040 #include <packet.h>
00041 #include <player.h>
00042 #include <robot_params.h>
00043    
00044 // Default max speeds
00045 #define MOTOR_DEF_MAX_SPEED 0.5
00046 #define MOTOR_DEF_MAX_TURNSPEED DTOR(100)
00047 
00048 /* 
00049  * Apparently, newer kernel require a large value (200000) here.  It only 
00050  * makes the initialization phase take a bit longer, and doesn't have any 
00051  * impact on the speed at which packets are received from P2OS 
00052  */
00053 #define P2OS_CYCLETIME_USEC 200000
00054 
00055 /* p2os constants */
00056 
00057 /* Command numbers */
00058 #define SYNC0 0
00059 #define SYNC1 1
00060 #define SYNC2 2
00061 
00062 #define PULSE 0
00063 #define OPEN 1
00064 #define CLOSE 2
00065 #define ENABLE 4
00066 #define SETA 5
00067 #define SETV 6
00068 #define SETO 7
00069 #define VEL 11
00070 #define RVEL 21
00071 #define SETRA 23
00072 #define SONAR 28
00073 #define STOP 29
00074 #define VEL2 32
00075 #define GRIPPER 33
00076 #define GRIPPERVAL 36
00077 #define TTY2 42         // Added in AmigOS 1.2
00078 #define GETAUX 43       // Added in AmigOS 1.2
00079 #define BUMP_STALL 44
00080 #define JOYDRIVE 47
00081 #define GYRO 58         // Added in AROS 1.8
00082 #define TTY3 66         // Added in AmigOS 1.3
00083 #define GETAUX2 67      // Added in AmigOS 1.3
00084 #define SOUND 90
00085 #define PLAYLIST 91
00086 
00087 /* Server Information Packet (SIP) types */
00088 #define STATUSSTOPPED   0x32
00089 #define STATUSMOVING    0x33
00090 #define ENCODER         0x90
00091 #define SERAUX          0xB0
00092 #define SERAUX2         0xB8    // Added in AmigOS 1.3
00093 #define GYROPAC         0x98    // Added AROS 1.8
00094 //#define PLAYLIST      0xD0
00095 
00096 /* Argument types */
00097 #define ARGINT          0x3B    // Positive int (LSB, MSB)
00098 #define ARGNINT         0x1B    // Negative int (LSB, MSB)
00099 #define ARGSTR          0x2B    // String (Note: 1st byte is length!!)
00100 
00101 /* gripper stuff */
00102 #define GRIPopen   1
00103 #define GRIPclose  2
00104 #define GRIPstop   3
00105 #define LIFTup     4
00106 #define LIFTdown   5
00107 #define LIFTstop   6
00108 #define GRIPstore  7
00109 #define GRIPdeploy 8
00110 #define GRIPhalt   15
00111 #define GRIPpress  16
00112 #define LIFTcarry  17
00113 
00114 /* CMUcam stuff */
00115 #define CMUCAM_IMAGE_WIDTH      80
00116 #define CMUCAM_IMAGE_HEIGHT     143
00117 #define CMUCAM_MESSAGE_LEN      10
00118 
00119 #define DEFAULT_P2OS_PORT "/dev/ttyS0"
00120 
00121 typedef struct player_p2os_data
00122 {
00123   player_position_data_t position;
00124   player_sonar_data_t sonar;
00125   player_gripper_data_t gripper;
00126   player_power_data_t power;
00127   player_bumper_data_t bumper;
00128   player_dio_data_t dio;
00129   player_aio_data_t aio;
00130   player_blobfinder_data_t blobfinder;
00131   player_position_data_t compass;
00132   player_position_data_t gyro;
00133 } __attribute__ ((packed)) player_p2os_data_t;
00134 
00135 // this is here because we need the above typedef's before including it.
00136 #include <sip.h>
00137 
00138 class SIP;
00139 
00140 class P2OS : public Driver 
00141 {
00142   private:
00143     player_p2os_data_t p2os_data;
00144     
00145     player_device_id_t position_id;
00146     player_device_id_t sonar_id;
00147     player_device_id_t aio_id;
00148     player_device_id_t dio_id;
00149     player_device_id_t gripper_id;
00150     player_device_id_t bumper_id;
00151     player_device_id_t power_id;
00152     player_device_id_t compass_id;
00153     player_device_id_t gyro_id;
00154     player_device_id_t blobfinder_id;
00155     player_device_id_t sound_id;
00156 
00157     // bookkeeping to only send new gripper I/O commands
00158     bool sent_gripper_cmd;
00159     player_gripper_cmd_t last_gripper_cmd;
00160 
00161     // bookkeeping to only send new sound I/O commands
00162     bool sent_sound_cmd;
00163     player_sound_cmd_t last_sound_cmd;
00164 
00165     int position_subscriptions;
00166     int sonar_subscriptions;
00167 
00168     SIP* sippacket;
00169   
00170     int SendReceive(P2OSPacket* pkt);
00171     void ResetRawPositions();
00172     /* toggle sonars on/off, according to val */
00173     void ToggleSonarPower(unsigned char val);
00174     /* toggle motors on/off, according to val */
00175     void ToggleMotorPower(unsigned char val);
00176     void HandleConfig(void);
00177     void GetCommand(void);
00178     void PutData(void);
00179     void HandlePositionCommand(player_position_cmd_t position_cmd);
00180     void HandleGripperCommand(player_gripper_cmd_t gripper_cmd);
00181     void HandleSoundCommand(player_sound_cmd_t sound_cmd);
00182 
00183     int param_idx;  // index in the RobotParams table for this robot
00184     int direct_wheel_vel_control; // false -> separate trans and rot vel
00185     int psos_fd;               // p2os device file descriptor
00186     const char* psos_serial_port;
00187     struct timeval lastblob_tv;
00188 
00189     // Max motor speeds (mm/sec,deg/sec)
00190     int motor_max_speed;
00191     int motor_max_turnspeed;
00192 
00193     // Bound the command velocities
00194     bool use_vel_band; 
00195 
00196     // Max motor accel/decel (mm/sec/sec, deg/sec/sec)
00197     short motor_max_trans_accel, motor_max_trans_decel;
00198     short motor_max_rot_accel, motor_max_rot_decel;
00199 
00200     int radio_modemp; // are we using a radio modem?
00201     int joystickp; // are we using a joystick?
00202     int bumpstall; // should we change the bumper-stall behavior?
00203 
00204   public:
00205 
00206     P2OS(ConfigFile* cf, int section);
00207 
00208     int Subscribe(player_device_id_t id);
00209     int Unsubscribe(player_device_id_t id);
00210 
00211     /* the main thread */
00212     void Main();
00213 
00214     int Setup();
00215     int Shutdown();
00216 
00217     void CMUcamReset();
00218     void CMUcamTrack(int rmin=0, int rmax=0, int gmin=0,
00219                           int gmax=0, int bmin=0, int bmax=0);
00220     void CMUcamStopTracking();
00221 };
00222 
00223 
00224 #endif

Generated on Tue May 3 14:15:35 2005 for Player by doxygen 1.3.6