00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
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
00045 #define MOTOR_DEF_MAX_SPEED 0.5
00046 #define MOTOR_DEF_MAX_TURNSPEED DTOR(100)
00047
00048
00049
00050
00051
00052
00053 #define P2OS_CYCLETIME_USEC 200000
00054
00055
00056
00057
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
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
00095
00096
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
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
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
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
00158 bool sent_gripper_cmd;
00159 player_gripper_cmd_t last_gripper_cmd;
00160
00161
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
00173 void ToggleSonarPower(unsigned char val);
00174
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;
00184 int direct_wheel_vel_control;
00185 int psos_fd;
00186 const char* psos_serial_port;
00187 struct timeval lastblob_tv;
00188
00189
00190 int motor_max_speed;
00191 int motor_max_turnspeed;
00192
00193
00194 bool use_vel_band;
00195
00196
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;
00201 int joystickp;
00202 int bumpstall;
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
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