Go to the documentation of this file.00001 #ifndef RFLEX_DRIVER_H
00002 #define RFLEX_DRIVER_H
00003
00004 #include <rflex/rflex_info.h>
00005 #include <pthread.h>
00006
00034 class RFLEX {
00035 public:
00036 RFLEX();
00037 virtual ~RFLEX();
00038
00042 int initialize(const char* devname);
00043
00051 void configureSonar(const unsigned long echoDelay, const unsigned long pingDelay,
00052 const unsigned long setDelay, const unsigned long val);
00053
00056 void setIrPower(const bool power);
00061 void setBrakePower(const bool power);
00062
00066 void setDigitalIoPeriod(const long period);
00067
00071 void setOdometryPeriod(const long period);
00072
00074 void motionSetDefaults();
00075
00078 bool getBrakePower() const {
00079 return brake;
00080 }
00081
00085 int getIrCount() const {
00086 return numIr;
00087 }
00088
00093 void setVelocity(const long transVelocity, const long rotVelocity,
00094 const long acceleration);
00095
00098 void sendSystemStatusCommand();
00099
00100 protected:
00101
00102 virtual void processDioEvent(unsigned char address, unsigned short data);
00103
00104 int distance;
00105 int bearing;
00106 int transVelocity;
00107 int rotVelocity;
00108
00109 int sonar_ranges[SONAR_MAX_COUNT];
00110 long voltage;
00111 bool brake;
00112
00113 unsigned short dioData[24];
00114
00115 int lcdX, lcdY;
00116 unsigned char * lcdData;
00117
00118 int numIr;
00119 unsigned char * irRanges;
00120 int home_bearing_found;
00121 int odomReady;
00122
00123 private:
00124 void parsePacket(const unsigned char* buffer);
00125 void parseMotReport(const unsigned char* buffer);
00126 void parseDioReport(const unsigned char* buffer);
00127 void parseIrReport(const unsigned char* buffer);
00128 void parseSysReport(const unsigned char* buffer);
00129 void parseSonarReport(const unsigned char* buffer);
00130 void parseJoyReport(const unsigned char* buffer);
00131
00132
00133 int fd;
00134 pthread_t thread;
00135 pthread_mutex_t writeMutex;
00136
00137 unsigned char readBuffer[BUFFER_SIZE];
00138 unsigned char writeBuffer[BUFFER_SIZE];
00139
00140 bool found;
00141 int offset;
00142
00143 static void *readThread(void *ptr);
00144
00152 bool sendCommand(const unsigned char port, const unsigned char id, const unsigned char opcode, const int length, unsigned char* data);
00153
00154 void readPacket();
00155 int readData();
00156 bool writePacket(const int length) const;
00157 unsigned char computeCRC(const unsigned char *buffer, const int n);
00158
00159
00160 RFLEX(const RFLEX &rflex);
00161 RFLEX &operator=(const RFLEX &rflex);
00162 };
00163 #endif