Jean-Yves Didier

Ajout de la bibliothèque gérant le GPS

Transition from ARCS1to2 made
However, some specificities for forms should be adapted
#ifndef __ATIME_H__
#define __ATIME_H__
#ifndef WIN32
#include <sys/time.h>
#endif
#include <time.h>
//#include <sys/timeb.h>
#ifdef WIN32
#include <winsock.h>
#include <windows.h>
//#include <sys/timeb.h>
#endif
class ATime
{
public:
ATime()
{
time_t now = time(NULL);
struct tm* tm= localtime(&now);
tm->tm_sec=0;
tm->tm_min=0;
tm->tm_hour=0;
offset = mktime(tm);
}
void start() { gettimeofday(&tv, NULL);}
double getValue() { return ((double)(tv.tv_sec - offset) + (double)tv.tv_usec /1000000.0) ; }
int elapsed()
{
struct timeval cmp;
gettimeofday(&cmp, NULL);
return (cmp.tv_sec - tv.tv_sec)*1000 + (cmp.tv_usec - tv.tv_usec) / 1000;
}
#ifdef WIN32
void gettimeofday(struct timeval *tmp, int toto) {
/* __timeb64 timebuffer;
_ftime64( &timebuffer );
if (0!=tmp) {
// following assertion prevents this:
// long maybe is smaller than __timeb64.time
// this may cause an overflow
tmp->tv_sec = static_cast<long>(timebuffer.time);
tmp->tv_usec = timebuffer.millitm * 1000;
}*/
DWORD msec= GetTickCount();
tmp->tv_sec = msec / 1000 ;
tmp->tv_usec = (msec % 1000) * 1000;
};
#endif
private:
struct timeval tv;
int offset;
};
#endif //__ATIME_H__
# Project modified by ARCS1to2
# Project modified by ARCS1to2
unix: TEMPLATE = lib
win32: TEMPLATE = vclib
LANGUAGE = C++
HEADERS += nmea.h
SOURCES += nmea.cpp
#The following line was changed from FORMS to FORMS3 by qt3to4
FORMS3 = gpswidget.ui
HEADERS += gpswwidget.h
HEADERS += gpstracker.h
HEADERS += gpstranslator.h
HEADERS += gpslog.h
HEADERS += gpstoogr.h
HEADERS += triggps.h
HEADERS += synsensor.h
HEADERS += synchro.h
SOURCES += gpstracker.cpp
SOURCES += gpstranslator.cpp
SOURCES += gpslog.cpp
SOURCES += gpstoogr.cpp
SOURCES += triggps.cpp
SOURCES += synsensor.cpp
SOURCES += synchro.cpp
HEADERS+= gpsserial.h
SOURCES+= gpsserial.cpp
SOURCES +=
MOC_DIR = ./moc
UI_DIR = ./ui
OBJECTS_DIR = ./obj
CONFIG += qt thread release
unix {
INCLUDEPATH+=/usr/local/include
LIBS+= -L/usr/local/lib
}
win32 {
INCLUDEPATH+=$$(ARCSDIR)/include
LIBS += -L$$(ARCSDIR)/lib -lcv -lcxcore -lcvaux -lhighgui
CONFIG += dll exceptions
DEFINES += _CRT_SECURE_NO_DEPRECATE
}
unix: QMAKE_POST_LINK=mv *.so* ../../../libs
win32: DLLDESTDIR = ../../../libs
#The following line was inserted by qt3to4
QT += qt3support
#The following line was inserted by qt3to4
CONFIG += uic3
ALXFILE = libgps.alx
OTHER_FILES += libgps.alx
arcslibrary.output = alm_${QMAKE_FILE_BASE}.cpp
arcslibrary.input = ALXFILE
arcslibrary.commands = arcslibmaker ${QMAKE_FILE_NAME}
arcslibrary.variable_out = SOURCES
QMAKE_EXTRA_COMPILERS += arcslibrary
INCLUDEPATH += $$(ARCSDIR)/include
LIBS += -L$$(ARCSDIR)/lib -larcs
CONFIG += dll
INCLUDEPATH += $$(ARCSDIR)/include
LIBS += -L$$(ARCSDIR)/lib -larcs
CONFIG += dll
<application>
<defines/>
<libraries>
<library name="../../../libs/libgps.so" />
</libraries>
<objects>
<object classname="GPSWWidget" persistent="true" id="widget" />
<object classname="GPSTracker" persistent="true" id="gpstrack" />
</objects>
<sheets>
<sheet id="start" >
<preconnection>
<init value="115200" type="int" slot="setBaudrate(int)" object="gpstrack" />
<init value="/dev/tts/USB0" type="string" slot="setDevice(QString)" object="gpstrack" />
<init value="1000" type="int" slot="setPeriod(int)" object="gpstrack" />
<init value="true" type="bool" slot="setThreaded(bool)" object="gpstrack" />
<init value="9" type="int" slot="setFrameCount(int)" object="gpstrack" />
<init value="" type="void" slot="init()" object="gpstrack" />
<init value="" type="void" slot="show()" object="widget" />
</preconnection>
<connection>
<wire objsource="gpstrack" objdest="widget" signal="sendNMEAFrame(NMEAFrame)" slot="displayNMEAFrame(NMEAFrame)" />
</connection>
<postconnection>
<init value="" type="void" slot="start()" object="gpstrack" />
</postconnection>
</sheet>
</sheets>
<statemachine terminal="end" initial="start" />
</application>
#!/bin/sh
# Small script to handle GPS under the toshiba portege 3500
# This should be adapted to become more generic if possible.
dmabt
rfcomm -i hci0 bind rfcomm0 00:80:37:28:32:96 2
chmod 666 /dev/rfcomm0
#include "gpslog.h"
#include <iostream>
using namespace std;
GPSLogger::GPSLogger(QObject* obj) : QObject(obj)
{
}
void GPSLogger::setPath(QString s)
{
chemin=s;
ofstream file;
file.open(chemin.ascii());
if (!file.is_open())
{
cerr << "Couldn't open file " << chemin.ascii() << endl;
return;
}
}
void GPSLogger::setTimestamp(double t)
{
ofstream file;
file.open(chemin.ascii(),ios::app);
if (!file.is_open())
{
cerr << "Couldn't open file " << chemin.ascii() << endl;
return;
}
file<<t<<endl;
file.close();
}
void GPSLogger::setStartTime(double t)
{
ofstream file;
file.open(chemin.ascii(),ios::app);
if (!file.is_open())
{
cerr << "Couldn't open file " << chemin.ascii() << endl;
return;
}
file<<t<<endl;
file.close();
}
void GPSLogger::setNMEAFrame(NMEAFrame tram)
{
ofstream file;
file.open(chemin.ascii(),ios::app);
if (!file.is_open())
{
cerr << "Couldn't open file " << chemin.ascii() << endl;
return;
}
/*CvScalar a;
CvSize size = cvGetSize(mat);
int col,row;
col = size.width;
row = size.height;
file << row <<" " << col<<" ";
for (int i=0;i<row;i++)
for (int j=0;j<col;j++)
{a=cvGet2D(mat,i,j); file << a.val[0]<<" ";}*/
file<<qPrintable(tram.getRawFrame())<<endl;
file.close();
emit sendToken("end");
}
LoadGps::LoadGps(QObject* obj) : QObject(obj)
{
autoSend = false;
initialized = true;
delay = 10;
connect(&selfTimer,SIGNAL(timeout()), this, SLOT(getData()));
starttime=true;
}
void LoadGps::setPath(QString s)
{
chemin=s;
}
void LoadGps::setVarStartTime(bool val)
{
starttime = val;
}
void LoadGps::init()
{
cout<<"[Lgps]init path:"<<qPrintable(chemin)<<endl;
file.open(chemin.ascii());
initialized = file.is_open();
if (!file.is_open())
{
cerr << "Couldn't open file " << chemin.ascii() << endl;
return;
}
if(starttime=true)
{
double val;
file>>val; cout<<val << endl;
emit sendTimeStart(val);
}
}
void LoadGps::getData()
{
if(!starttime)
{
string s;
if (!initialized)
return;
file >> s; cout<<s<<endl;
if (file.eof()) {
cout<<"end of file"<<endl;
if (autoSend)
stop();
initialized = false;
file.clear();
file.close();
emit sendToken("end");
}
else emit sendNMEAFrame(NMEAFrame(s.c_str()));
//if (file.eof()) emit sendToken("end");
}
else
{
string TGSV1, TGSA, TZDA, TRMC, TGGA, TGLL, TVTG, TGSV2, TGSV3;
double time;
if (!initialized)
return;
file >> time >> TGSV1 >> TGSA >> TZDA >> TRMC >> TGGA >> TGLL >> TVTG >> TGSV2 >> TGSV3;
// cout<< time <<endl;
// cout<< TGSV1 <<" "<< TGSA <<" "<< TZDA << " "<< TRMC <<" "<< TGGA << " "<< TGLL << " " << TVTG << " " << TGSV2 <<" " << TGSV3<<endl;
if (file.eof()) {
cout<<"end of file"<<endl;
if (autoSend)
stop();
initialized = false;
file.clear();
file.close();
emit sendToken("end");
}
else
{
emit sendTime(time);
emit sendNMEAFrame(NMEAFrame(TGGA.c_str()));
}
}
}
void LoadGps::start()
{
if (!initialized)
return;
if (autoSend)
{
if (delay)
selfTimer.start(delay);
else
while (initialized)
getData();
}
}
void LoadGps::stop()
{
if (autoSend)
{
selfTimer.stop();
}
}
#ifndef __GPSLOG_H__
#define __GPSLOG_H__
#include "atime.h"
#include <QObject>
#include <QTimer>
#include <opencv/cv.h>
#include "nmea.h"
#include <fstream>
class GPSLogger : public QObject
{
Q_OBJECT
public :
GPSLogger(QObject* parent=0) ;
public slots :
void setPath(QString s);
void setNMEAFrame(NMEAFrame tram);
void setTimestamp(double t);
void setStartTime(double t);
signals :
void sendToken(QString s);
private:
QString chemin;
};
class LoadGps : public QObject
{
Q_OBJECT
public :
LoadGps(QObject* parent=0);
public slots :
void setPath(QString s);
void init();
void getData();
void start();
void stop();
void setThreaded(bool b) { autoSend = b; }
void setDelay(int i) { delay = i; }
void setVarStartTime(bool val);
signals :
void sendNMEAFrame(NMEAFrame t);
void sendTimeStart(double t);
void sendTime(double t);
void sendToken(QString s);
private:
QString chemin;
bool initialized;
std::ifstream file;
QTimer selfTimer;
bool autoSend;
ATime startTime;
int delay;
bool starttime;
};
#endif
#include "gpsserial.h"
#include <cstdio>
GPSSerial::GPSSerial()
{
portOpen = false;
}
bool GPSSerial::openPort(const int portNumber, BaudRates baudrate, const unsigned long inqueueSize, const unsigned long outqueueSize)
{
if (portOpen)
return true ;
char filename[15];
#ifdef WIN32
sprintf(filename,"\\\\.\\COM%d",portNumber);
#else
sprintf(filename,"/dev/ttyS%d",portNumber);
#endif
return openPort(filename, baudrate, inqueueSize, outqueueSize);
}
bool GPSSerial::openPort(const char *portName, BaudRates baudrate, const unsigned long inqueueSize, const unsigned long outqueueSize)
{
if (portOpen)
return true ;
#ifdef WIN32
wchar_t wPortName[15];
mbstowcs(wPortName,portName, 15);
fd = CreateFile((LPCWSTR)wPortName, GENERIC_READ, 0, NULL, OPEN_EXISTING, 0, NULL);
if (fd == INVALID_HANDLE_VALUE)
return false;
// Once here, port is open
portOpen = true;
//Get the current state & then change it
DCB dcb;
GetCommState(fd, &dcb); // Get current state
dcb.BaudRate = baudrate; // Setup the baud rate
dcb.Parity = NOPARITY; // Setup the Parity
dcb.ByteSize = 8; // Setup the data bits
dcb.StopBits = ONESTOPBIT; // Setup the stop bits
dcb.fDsrSensitivity = FALSE; // Setup the flow control
dcb.fOutxCtsFlow = FALSE; // NoFlowControl:
dcb.fOutxDsrFlow = FALSE;
dcb.fOutX = FALSE;
dcb.fInX = FALSE;
if (!SetCommState(fd, (LPDCB)&dcb))
{
portOpen = false;
return false;
}
// Set COM timeouts
COMMTIMEOUTS CommTimeouts;
GetCommTimeouts(fd,&CommTimeouts); // Fill CommTimeouts structure
// immediate return if data is available, wait 1ms otherwise
CommTimeouts.ReadTotalTimeoutConstant = 1;
CommTimeouts.ReadIntervalTimeout = MAXDWORD;
CommTimeouts.ReadTotalTimeoutMultiplier = MAXDWORD;
// immediate return whether data is available or not
SetCommTimeouts(fd, &CommTimeouts); // Set CommTimeouts structure
// Other initialization functions
SetupComm(fd,inqueueSize,outqueueSize); // Set queue size
SetCommMask(fd, EV_CTS | EV_DSR | EV_BREAK | EV_RING | EV_RXCHAR);
// Remove any 'old' data in buffer
PurgeComm(fd, PURGE_TXCLEAR | PURGE_RXCLEAR);
return true;
#else
struct termios options;
/* Open port */
fd = open(portName, O_RDONLY | O_NOCTTY);
if (fd < 0)
return false;
// Once here, port is open
portOpen = true;
/* Start configuring of port for non-canonical transfer mode */
// Get current options for the port
tcgetattr(fd, &options);
// Set baudrate.
cfsetispeed(&options, baudrate);
cfsetospeed(&options, baudrate);
// Enable the receiver and set local mode
options.c_cflag = (CLOCAL | CREAD | CSIZE | CS8 );
// Set character size to data bits and set no parity Mask the characte size bits
//options.c_cflag &= ~(CSIZE|PARENB);
//options.c_cflag |= CS8; // Select 8 data bits
//options.c_cflag &= ~CSTOPB; // send 1 stop bit
// Disable hardware flow control
//options.c_cflag &= ~CRTSCTS;
options.c_lflag &= ~(ECHO|ECHONL|ICANON|ISIG|IEXTEN);
// Disable software flow control
options.c_iflag &= 0; //~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON);
// Set Raw output
options.c_oflag &= ~OPOST;
// Timeout 0.005 sec for first byte, read minimum of 0 bytes
options.c_cc[VMIN] = 0;
options.c_cc[VTIME] = 5;
// Set the new options for the port
if ( tcsetattr(fd,TCSANOW, &options) < 0)
{
portOpen = false;
return false;
}
tcflush(fd, TCIOFLUSH);
return true;
#endif
}
void GPSSerial::flush()
{
if (portOpen)
{
#ifdef WIN32
PurgeComm(fd, PURGE_TXCLEAR | PURGE_RXCLEAR);
#else
tcflush(fd, TCIOFLUSH);
#endif
}
}
void GPSSerial::close()
{
if (portOpen)
{
#ifdef WIN32
flush();
CloseHandle(fd);
#else
::close(fd);
#endif
}
portOpen = false;
}
int GPSSerial::readNMEAFrame(unsigned char* buffer, int maxSize)
{
if (!portOpen)
return 0;
buffer[maxSize-1] = '\0';
int i=0;
#ifdef WIN32
DWORD bytes;
BOOL retval;
do
{
retval = ReadFile(fd, &buffer[i], 1 , &bytes, NULL);
i += bytes ;
} while ( i < maxSize - 1 && buffer[i-1] != '\x0a' && retval );
#else
int bytes;
do
{
bytes = read(fd, &buffer[i],1);
i ++ ;
} while ( i < maxSize - 1 && buffer[i-1] != '\x0a' && bytes > 0);
#endif
buffer[i] = '\0';
return i;
}
int GPSSerial::waitNMEAFrame(unsigned char* buffer, int maxSize)
{
if (!portOpen )
return 0;
#ifdef WIN32
BOOL retval;
DWORD evt;
retval = WaitCommEvent(fd,&evt, NULL);
if (retval )
{
if (evt & EV_DSR || evt & EV_CTS || evt & EV_RXCHAR )
readNMEAFrame(buffer, maxSize);
else return 0;
}
else
return 0;
#else
struct timeval tv;
int retval;
fd_set rfds;
FD_ZERO(&rfds);
FD_SET(fd,&rfds);
tv.tv_sec = 10 ;
tv.tv_usec = 0 ;
retval = select(fd + 1, &rfds, NULL,NULL, &tv);
if (retval == -1)
return 0;
else
return readNMEAFrame(buffer, maxSize);
#endif
}
#ifndef __GPSSERIAL_H__
#define __GPSSERIAL_H__
#ifdef WIN32
#include <windows.h>
#include <conio.h>
#include <time.h>
#else
#include <fcntl.h> /* POSIX Standard: 6.5 File Control Operations */
#include <termios.h> /* terminal i/o system, talks to /dev/tty* ports */
#include <unistd.h> /* Read function */
#include <sys/time.h> /* gettimeofday function */
#include <sys/select.h>
#endif
/*! \brief Low-level class for serial connection with GPS.
*
* This class is intended to be cross-platform as much as possible.
* It establishes a serial connection to a GPS. The intent is to recieve NMEA frames.
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class GPSSerial
{
public:
GPSSerial(); //!< GPS Constructor
~GPSSerial() { close(); } //!< GPS Destructor
/*! \brief Portable baudrates definitions
*/
#ifdef WIN32
enum BaudRates { PBR_110 = CBR_110, PBR_300 = CBR_300, PBR_600 = CBR_600,
PBR_1200 = CBR_1200, PBR_2400 = CBR_2400, PBR_4800 = CBR_4800,
PBR_9600 = CBR_9600, PBR_19200 = CBR_19200, PBR_38400 = CBR_38400,
PBR_57600 = CBR_57600, PBR_115200 = CBR_115200 };
#else
enum BaudRates { PBR_110 = B110, PBR_300 = B300, PBR_600 = B600,
PBR_1200 = B1200, PBR_2400 = B2400, PBR_4800 = B4800,
PBR_9600 = B9600, PBR_19200 = B19200, PBR_38400 = B38400,
PBR_57600 = B57600, PBR_115200 = B115200 };
#endif
/*! \brief Opens the serial connection between PC and GPS
*
* This method is mainly intended to connect a serial connection sous windows.
*
* \param portNumber a port number, that is to say the number of the COM port.
*/
bool openPort(const int portNumber, BaudRates baudrate = PBR_4800, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
/*! \brief Opens the serial connection between PC and GPS
*
* This method is the generic purpose connection tool.
* You just need to indicate which file is representing the serial port.
* Under unix, this might be <tt>/dev/ttyS0</tt> whereas under windows it should be <tt>\\\\.\\COM0</tt>
* To simplify configuration: the serial port is intended to communicate with these parameters :
* <ul>
* <li> 8 bits for each data byte ;</li>
* <li> no parity check ;</li>
* <li> 1 bit stop ;</li>
* <li> no hardware control.</li>
* </ul>
* \param portName name of the file representing the serial device.
* \param baudrate a baudrate for serial communication ;
* \param inqueueSize (for windows use only) the queue size for input ;
* \param outqueueSize (for windows use only) the queue size for output.
* \return <tt>true</tt> if the communication is established, <tt>false</tt> otherwise.
*/
bool openPort(const char *portName, BaudRates baudrate = PBR_4800, const unsigned long inqueueSize = 4096, const unsigned long outqueueSize = 1024);
bool isPortOpen() const { return portOpen; }
/*! \brief Waits for an NMEA Frame from the serial line.
*
* This uses something similar to the select system call under unix.
* \param buffer a buffer where NMEA Frame should be written. Note this buffer should be allocated.
* \param maxSize the buffer size.
* \return the number of read characters.
*/
int waitNMEAFrame(unsigned char* buffer,int maxSize=128);
/*! \brief Reads an NMEA Frame from the serial line.
*
* \param buffer a buffer where NMEA Frame should be written. Note this buffer should be allocated.
* \param maxSize the buffer size.
* \return the number of read characters.
*/
int readNMEAFrame(unsigned char* buffer,int maxSize=128);
void close();//!< Closes the serial port
void flush();//!< Flushes all the data in the internal buffer associated to serial line.
private:
#ifdef WIN32
Qt::HANDLE fd ;
#else
int fd;
#endif
bool portOpen;
};
#endif //__GPSSERIAL_H__
#include "gpsserial.h"
#include <iostream>
/* Simple GPS serial test program
compile with :
g++ gpstester.cpp gpsserial.cpp -o testgps
*/
int main(int argc, char* argv[])
{
GPSSerial gps;
int i;
gps.openPort("/dev/rfcomm0", GPSSerial::PBR_115200);
unsigned char frame[128];
if (!gps.isPortOpen())
{
std::cerr << "Port not opened" << std::endl;
}
for(int i=0; i < 100; i++)
{
int res;
res = gps.readNMEAFrame(frame,128);
if (res > 3)
std::cout << "Frame #" << i << " " << res << " " << frame ;
}
gps.close();
return 0;
}
#include "gpstoogr.h"
#include <iostream>
using namespace std;
GpsToOgr::GpsToOgr(QObject* obj) : QObject(obj)
{
}
void GpsToOgr::setTime(double t)
{temps = t;}
void GpsToOgr::setNMEAFrame(NMEAFrame f)
{
// cout<<f.getRawFrame()<<endl;
double x,y;
bool val=false;
NMEATime time;
NMEAAngle lon;
NMEAAngle lat;
int dop=0;
int sv=0;
if (f.extractType() == "GGA")
{
NMEAFrameGGA frame = f;
lon = frame.getLongitude();
lat = frame.getLatitude();
if (lon.valid)
x = lon.degrees + lon.minutes/60;
if (lat.valid)
y = lat.degrees + lat.minutes/60 ;
if(lon.valid && lat.valid) val=true;
time = frame.getUTCTime();
dop = frame.getDOP();
sv = frame.getSVNumber();
if (val)
cout<<1<<fixed<< " " << temps << " " <<(time.hours+2)*3600+time.minutes*60+time.seconds<<" "/*<<sv<<" "<<dop<<" "<<x<<" "<<y<<" "*/;
//cout<<fixed <<x<<" "<<y<<endl;
}
if (f.extractType() == "GLL")
{
NMEAFrameGLL frame (f);
lon = frame.getLongitude();
lat = frame.getLatitude();
if (lon.valid)
x = lon.degrees + lon.minutes/60;
if (lat.valid)
y = lat.degrees + lat.minutes/60 ;
if(lon.valid && lat.valid) val=true;
time = frame.getUTCTime();
if (val)
cout<<2<<fixed <<" "<<(time.hours+2)*3600+time.minutes*60+time.seconds<<" "/*<<sv<<" "<<dop<<" "<<x<<" "<<y<<" "*/;
//if (val)
// cout<<fixed<<2<<" "<<(time.hours+2)*3600+time.minutes*60+time.seconds<<" "<<sv<<" "<<dop<<" "<<x<<" "<<y<<" ";
//cout<<fixed <<x<<" "<<y<<endl;
}
if (f.extractType() == "RMC")
{
NMEAFrameRMC frame = f;
lon = frame.getLongitude();
lat = frame.getLatitude();
if (lon.valid)
x = lon.degrees + lon.minutes/60;
if (lat.valid)
y = lat.degrees + lat.minutes/60 ;
if(lon.valid && lat.valid) val=true;
time = frame.getUTCTime();
if (val)
cout<<3<<fixed <<" "<<(time.hours+2)*3600+time.minutes*60+time.seconds<<" "/*<<sv<<" "<<dop<<" "<<x<<" "<<y<<" "*/;
//if(val)
// cout<<fixed<<3<<" "<<(time.hours+2)*3600+time.minutes*60+time.seconds<<" "<<sv<<" "<<dop<<" "<<x<<" "<<y<<" ";
//cout<<fixed <<x<<" "<<y<<endl;
}
if (val)
{
//cout<<"Coordonnes gographiques :"<<x<<" "<<y<<endl;
emit sendCoordinates(x,y);
emit sendTime(time);
}
else
{
//cout<<"NO data"<<endl;
emit sendNext();
}
}
SetAltitude::SetAltitude(QObject* obj) : QObject(obj)
{
}
void SetAltitude::setCoordinates(double x, double y)
{
CvMat *m;
m = cvCreateMat(3,1,CV_32FC1);
//cout<<"Position: "<<x<<" "<<y<<" "<<z<<endl;
cvSet1D(m,0,cvRealScalar(x)); cvSet1D(m,1,cvRealScalar(y)); cvSet1D(m,2,cvRealScalar(z));
emit sendCoordinates(m);
emit sendToken("end");
cvReleaseMat(&m);
}
#ifndef __GPSTOOGR_H__
#define __GPSTOOGR_H__
#include <QObject>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include "nmea.h"
class GpsToOgr : public QObject
{
Q_OBJECT
public :
GpsToOgr(QObject* parent=0) ;
public slots :
void setNMEAFrame(NMEAFrame f);
void setTime(double t);
signals :
void sendCoordinates(double x, double y);
void sendTime(NMEATime t);
void sendNext();
private:
double temps;
};
class SetAltitude : public QObject
{
Q_OBJECT
public:
SetAltitude(QObject* parent=0);
public slots:
void setZ(double val) {z=val;};
void setCoordinates(double x, double y);
signals:
void sendCoordinates(CvMat *m);
void sendToken(QString s);
private:
double z;
};
#endif
#include "gpstracker.h"
#define NUM_BAUDRATES 11
long unsigned int GPSTracker::baudrates[][2] = {
{ GPSSerial::PBR_110, 110 }, { GPSSerial::PBR_300, 300 }, { GPSSerial::PBR_600, 600 },
{ GPSSerial::PBR_1200, 1200 }, { GPSSerial::PBR_2400, 2400 }, { GPSSerial::PBR_4800, 4800 },
{ GPSSerial::PBR_9600, 9600 }, { GPSSerial::PBR_19200, 19200}, { GPSSerial::PBR_38400, 38400 },
{ GPSSerial::PBR_57600, 57600 }, { GPSSerial::PBR_115200, 115200 }};
GPSTracker::GPSTracker(QObject* parent) : QObject(parent)
{
period = 0;
baudrate = GPSSerial::PBR_4800;
port = 0;
frameCount =1;
device = "/etc/ttyS0" ;
autoSend = false;
initialized = false;
}
GPSTracker::~GPSTracker()
{
if (gps.isPortOpen())
{
gps.flush();
gps.close();
}
}
void GPSTracker::init()
{
#ifdef WIN32
if (!gps.openPort(port, (GPSSerial::BaudRates)computeRealBaudrate()))
#else
if (!gps.openPort(device.ascii(),(GPSSerial::BaudRates)computeRealBaudrate()))
#endif
{
#ifdef WIN32
std::cerr << "[GPS] Cannot access GPS. num port" << port << std::endl;
#else
std::cerr << "[GPS] Cannot access GPS. " << device.ascii() << std::endl;
#endif
return ;
}
initialized = true;
startTime.start(); // = QTime::currentTime();
double ts = startTime.getValue();//(double)(startTime.hour()*3600 + startTime.minute()*60 + startTime.second())
//+ (double)(startTime.msec())/1000.0;
std::cout<<std::fixed<<"[GPS] start "<<ts<<std::endl;
emit sendStartTime(ts);
}
void GPSTracker::start()
{
if (!initialized)
return ;
//std::cout << "[GPS] Starting recieving GPS Frames" << std::endl;
if (autoSend)
{
std::cout << "[GPS] GPS in threaded mode" << std::endl;
connect( &selfTimer, SIGNAL(timeout()), this, SLOT(sendData()));
selfTimer.start(period);
gps.flush();
}
}
void GPSTracker::stop()
{
if (!initialized)
return ;
if (autoSend)
{
selfTimer.stop();
disconnect(&selfTimer, SIGNAL(timeout()), this, SLOT(sendData()));
}
}
void GPSTracker::sendData()
{
if( !initialized)
return;
unsigned char frameContent[128];
int res;
//std::cout << "[GPS] Recieving frames " << std::endl;
startTime.start();
// emit sendTimeStamp(startTime.getValue());
//std::cout << "[GPS] elapsed time " << startTime.getValue() << std::endl;
for (int i = 0; i < frameCount; i++)
{
do
{
res = gps.readNMEAFrame(frameContent,128);
} while (res < 3);
emit sendTimeStamp(startTime.getValue());
sendNMEAFrame(NMEAFrame(QString((char*)frameContent)));
}
// std::cout << "[GPS] frames sent" << std::endl;
}
long unsigned int GPSTracker::computeRealBaudrate()
{
if (baudrate > baudrates[NUM_BAUDRATES-1][1])
return baudrates[NUM_BAUDRATES-1][0];
for (int i=1; i< NUM_BAUDRATES; i++)
{
if ( baudrate < baudrates[i][1])
{
std::cerr << "[GPS] Setting baudrate to "<< baudrates[i-1][1] << " bps"<<std::endl;
return baudrates[i-1][0];
}
}
return GPSSerial::PBR_4800 ;
}
#ifndef __GPSTRACKER_H__
#define __GPSTRACKER_H__
#include <QObject>
#include <QTimer>
#include "gpsserial.h"
#include "nmea.h"
#include "../../include/atime.h"
/*! \defgroup gps GPS sensor related classes.
*
* This is a set of classes built to collect, extract and parse GPS Data using NMEA Frames collected
* over a serial line.
* \ingroup tracker
*/
/*! \brief The ARCS Component to collect GPS data over a serial line.
*
* The GPS data collection is performed using a GPSSerial object.
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class GPSTracker : public QObject
{
Q_OBJECT
public:
GPSTracker(QObject* parent=0); //!< ARCS Constructor
~GPSTracker(); //!< ARCS Destructor
public slots:
/*! \brief The port number to open
*
* This should be called before init().
* It sets the port number to use to collect serial data from GPS.
* This is mainly for windows use.
* \param i the port number to use e.g. if using COM0, you should use 0 as a parameter of this function.
*/
void setPort(int i) { port = i;}
/*! \brief The device filename to open.
* This should be called before init().
* \param s the device filename.
*/
void setDevice(QString s) { device = s;}
/*!\brief Inits the GPS serial line.
* From this point, data can be collected.
*/
void init();
/*! \brief Tells wether the data collection process is pseudo-threaded or not.
* Events are actually used so this is not really a thread.
* This must be called before start().
* When start() is called, events may be triggered periodically.
* This event will in return trigger the sendData() slot.
* \param b Set it to <tt>true</tt> to activate pseudo-threaded behaviour.
*/
void setThreaded(bool b) {autoSend = b; }
/*! \brief Sets the baudrate of the serial line.
*/
void setBaudrate(int i) { baudrate = i; }
/*! \brief Sets the period of a data collection cycle.
* \param i The period expressed in milliseconds. Usually you will have something around 1000 msec.
*/
void setPeriod(int i) { period=i; }
/*!\brief Sets the number of frames constituing the data to read.
* A GPS can send several NMEA frames at the same time.
* This is intended to group the frame packets in one send.
* \param i The number of frames returned at once by the GPS reciever.
*/
void setFrameCount(int i) { frameCount = i; }
void start(); //!< Starts the GPS data collection. init() muste have been called before.
void stop(); //!< Stops the GPS data collection.
/*! \brief The actual collection process
*
* Triggers a sendNMEAFrame() signal.
*/
void sendData();
signals:
void sendNMEAFrame(NMEAFrame); //!< Sends the newly acquired NMEAFrame
void sendTimeStamp(double); //!< Sends a timestamp associated to the time of nmea frame acquisition
void sendStartTime(double);
private:
long unsigned int computeRealBaudrate();
static long unsigned int baudrates[][2];
GPSSerial gps;
QTimer selfTimer;
int period;
int baudrate;
int port;
QString device;
bool autoSend;
bool initialized;
int frameCount;
ATime startTime;
};
#endif //__GPSTRACKER_H__
#include "gpstranslator.h"
GPSTranslator::GPSTranslator(QObject* parent) : QObject(parent)
{
clearData();
frameAmount = 1;
currentData.validityMask = 0;
frameCnt = 0;
}
void GPSTranslator::clearData()
{
currentData.validityMask = 0;
frameCnt = 0;
}
double GPSTranslator::nmeaAngleToDouble(NMEAAngle a)
{
double res = a.degrees + a.minutes / 60.0 ;
switch (a.direction)
{
case 'S': case 'E':
res = -res ;
}
return res;
}
float GPSTranslator::nmeaTimeToFloat(NMEATime t)
{
return (t.seconds + (t.hours * 60 + t.minutes) * 60 );
}
void GPSTranslator::handleGGAFrame(NMEAFrameGGA frame)
{
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
NMEATime tm = frame.getUTCTime();
if (lon.valid && !(currentData.validityMask & GPS_LONG ))
{
currentData.longitude = nmeaAngleToDouble(lon);
currentData.validityMask |= GPS_LONG ;
}
if (lat.valid && !(currentData.validityMask & GPS_LAT))
{
currentData.latitude = nmeaAngleToDouble(lat);
currentData.validityMask |= GPS_LAT ;
}
if (tm.valid && ! (currentData.validityMask & GPS_TIME))
{
currentData.time = nmeaTimeToFloat(tm);
currentData.validityMask |= GPS_TIME ;
}
if (! ( currentData.validityMask & GPS_NBSAT) )
currentData.nbSat = frame.getSVNumber();
if (! ( currentData.validityMask & GPS_Z ))
currentData.z = frame.getAntennaHeight();
if (! ( currentData.validityMask & GPS_DOP))
currentData.dop = frame.getDOP();
currentData.validityMask |= GPS_DOP | GPS_NBSAT | GPS_Z ;
}
void GPSTranslator::handleRMCFrame(NMEAFrameRMC frame)
{
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
float cape = frame.getTrackAngle();
NMEATime tm = frame.getUTCTime();
if (lon.valid && !(currentData.validityMask & GPS_LONG ))
{
currentData.longitude = nmeaAngleToDouble(lon);
currentData.validityMask |= GPS_LONG ;
}
if (lat.valid && !(currentData.validityMask & GPS_LAT))
{
currentData.latitude = nmeaAngleToDouble(lat);
currentData.validityMask |= GPS_LAT ;
}
if (tm.valid && ! (currentData.validityMask & GPS_TIME))
{
currentData.time = nmeaTimeToFloat(tm);
currentData.validityMask |= GPS_TIME ;
}
if (! (currentData.validityMask & GPS_CAPE))
{
currentData.cape = cape;
currentData.validityMask |= GPS_CAPE ;
}
}
void GPSTranslator::handleVTGFrame(NMEAFrameVTG frame)
{
float cape = frame.getTrackAngle();
if ( ! (currentData.validityMask & GPS_CAPE))
{
currentData.cape = cape;
currentData.validityMask |= GPS_CAPE ;
}
if ( ! (currentData.validityMask & GPS_SPEED))
currentData.speed = frame.getKMSpeed();
currentData.validityMask |= GPS_SPEED;
}
void GPSTranslator::setNMEAFrame(NMEAFrame nmea)
{
if (nmea.extractType() == "GGA" )
handleGGAFrame(NMEAFrameGGA(nmea));
if (nmea.extractType() == "RMC" )
handleRMCFrame(NMEAFrameRMC(nmea));
if (nmea.extractType() == "VTG")
handleVTGFrame(NMEAFrameVTG(nmea));
/* put here something to determine how many frames have been processed */
frameCnt ++ ;
if (frameCnt == frameAmount)
{
emit sendGPSData(currentData);
clearData();
}
}
#ifndef __GPS_TRANSLATOR_H__
#define __GPS_TRANSLATOR_H__
#include <QObject>
#include "nmea.h"
//* \todo maintain compatibility of structs
enum GPSValidity {
GPS_TIME = 0x01,
GPS_LONG = 0x02,
GPS_LAT = 0x04,
GPS_DOP = 0x08,
GPS_NBSAT = 0x10,
GPS_Z = 0x20,
GPS_SPEED = 0x40,
GPS_CAPE = 0x80
};
/*! \brief This structure should contain the data gathered from
* the GPS reciever.
*
* The GPS data needed are :
* <ul>
* <li>the clock ;</li>
* <li>dop (hdop and pdop) if available ; </li>
* <li>nb_sat ;</li>
* <li>longitude ;</li>
* <li>latiude ; </li>
* <li>speed over ground ;</li>
* <li>cape </li>
* </ul>
* \ingroup gps
*/
typedef struct {
float time; //!< time elapsed since 00:00
float dop; //!< dop factor
int nbSat; //!< number of satelites
double longitude; //!< longitude
double latitude; //!< latitude
double z; //!< height
float speed; //!< speed over ground
double cape; //!< direction
unsigned char validityMask;
} GPSData ;
/*! \brief This class should handle NMEA Frames and translate them into a GPSData structure.
*
* \author Jean-Yves Didier
* \date September, the 26th, 2008
* \ingroup gps
*/
class GPSTranslator : public QObject
{
Q_OBJECT
public:
GPSTranslator(QObject* parent=0); //!< ARCS Constructor
public slots:
void setFrameAmount(int i) { frameAmount = i; } //!< Sets the number of frame to process before sending gps data.
void setNMEAFrame(NMEAFrame nmea); //!< Sets the nmea frame to process
signals:
void sendGPSData(GPSData gd); //!< Sends the newly processed GPS Data
private:
void handleGGAFrame(NMEAFrameGGA frame);
void handleRMCFrame(NMEAFrameRMC frame);
void handleVTGFrame(NMEAFrameVTG frame);
void clearData();
double nmeaAngleToDouble(NMEAAngle a);
float nmeaTimeToFloat(NMEATime t);
int frameAmount;
GPSData currentData;
int frameCnt;
};
#endif //__GPS_TRANSLATOR_H__
<!DOCTYPE UI><UI version="3.3" stdsetdef="1">
<class>GPSWidget</class>
<widget class="QWidget">
<property name="name">
<cstring>GPSWidget</cstring>
</property>
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>203</width>
<height>140</height>
</rect>
</property>
<property name="caption">
<string>GPS Values</string>
</property>
<widget class="QLabel">
<property name="name">
<cstring>label2</cstring>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>10</y>
<width>70</width>
<height>21</height>
</rect>
</property>
<property name="text">
<string>Latitude :</string>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>label1</cstring>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>40</y>
<width>70</width>
<height>21</height>
</rect>
</property>
<property name="text">
<string>Longitude :</string>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>label4</cstring>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>70</y>
<width>70</width>
<height>21</height>
</rect>
</property>
<property name="text">
<string>DOP :</string>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>latitude</cstring>
</property>
<property name="geometry">
<rect>
<x>80</x>
<y>10</y>
<width>111</width>
<height>20</height>
</rect>
</property>
<property name="frameShape">
<enum>Box</enum>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>longitude</cstring>
</property>
<property name="geometry">
<rect>
<x>80</x>
<y>40</y>
<width>111</width>
<height>20</height>
</rect>
</property>
<property name="frameShape">
<enum>Box</enum>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>dop</cstring>
</property>
<property name="geometry">
<rect>
<x>80</x>
<y>70</y>
<width>111</width>
<height>20</height>
</rect>
</property>
<property name="frameShape">
<enum>Box</enum>
</property>
<property name="text">
<string>-</string>
</property>
</widget>
<widget class="QLCDNumber">
<property name="name">
<cstring>sv</cstring>
</property>
<property name="geometry">
<rect>
<x>120</x>
<y>100</y>
<width>70</width>
<height>30</height>
</rect>
</property>
<property name="numDigits">
<number>2</number>
</property>
</widget>
<widget class="QLabel">
<property name="name">
<cstring>label3</cstring>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>100</y>
<width>110</width>
<height>30</height>
</rect>
</property>
<property name="text">
<string>Satellites in view :</string>
</property>
</widget>
</widget>
<includes>
<include location="local" impldecl="in declaration">nmea.h</include>
<include location="local" impldecl="in implementation">gpswidget.ui.h</include>
</includes>
<slots>
<slot specifier="non virtual">displayNMEAFrame( NMEAFrame f )</slot>
</slots>
<layoutdefaults spacing="6" margin="11"/>
</UI>
/****************************************************************************
** ui.h extension file, included from the uic-generated form implementation.
**
** If you want to add, delete, or rename functions or slots, use
** Qt Designer to update this file, preserving your code.
**
** You should not define a constructor or destructor in this file.
** Instead, write your code in functions called init() and destroy().
** These will automatically be called by the form's constructor and
** destructor.
*****************************************************************************/
/*! \class GPSWidget A simple widget to display GPS values
* \author Jean-Yves Didier
* \date February, the 4th, 2008
* \ingroup gps
*/
/*! \brief This slot intends to display GPS values
* \param f A NMEAFrame containing GPS data.
*/
void GPSWidget::displayNMEAFrame( NMEAFrame f )
{
longitude->setText("-NC-");
latitude->setText("-NC-");
//std::cout<<f.getRawFrame()<<std::endl;
if (f.extractType() == "GGA")
{
//std::cout<<"GGA trame"<<std::endl;
NMEAFrameGGA frame(f); //!< \todo Assess this dirty line. It should do the trick.
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
if (lon.valid)
{
QString llon = QString::number(lon.degrees) + "°" + QString::number(lon.minutes) + "' " + lon.direction ;
longitude->setText(llon);
longitude->update();
std::cout<<"longitude "<<qPrintable(llon)<<std::endl;
}
if (lat.valid)
{
QString llat = QString::number(lat.degrees) + "°" + QString::number(lat.minutes) + "' " + lat.direction ;
latitude->setText(llat);
latitude->update();
std::cout<<"latitude "<<qPrintable(llat)<<std::endl;
}
dop->setText(QString::number(frame.getDOP()));
dop->update();
sv->display(frame.getSVNumber());
}
}
#ifndef __GPSWWIDGET_H__
#define __GPSWWIDGET_H__
#include "ui/gpswidget.h"
/*! \brief This is an ARCS wrapper for the GPSWidget control panel.
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class GPSWWidget : public GPSWidget
{
Q_OBJECT
public:
/*! ARCS Constructor
*/
GPSWWidget(QObject* parent=0)
: GPSWidget(dynamic_cast<QWidget*>(parent)) {}
};
#endif //__GPSWWIDGET_H__
#include <metalibrary/metalibrarytoolkit.h>
#include "gpswwidget.h"
#include "gpstracker.h"
#include "gpstranslator.h"
#include "gpslog.h"
#include "gpstoogr.h"
#include "triggps.h"
#include "synsensor.h"
#include "synchro.h"
METALIB_BEGIN
METALIB_OBJECT(GPSTracker)
METALIB_OBJECT(GPSWWidget)
METALIB_OBJECT(GPSTranslator)
METALIB_OBJECT(GPSLogger)
METALIB_OBJECT(LoadGps)
METALIB_OBJECT(GpsToOgr)
METALIB_OBJECT(SetAltitude)
METALIB_OBJECT(SynSensor)
METALIB_OBJECT(GpsTrigger)
METALIB_OBJECT(Synchro)
METALIB_END
#include "nmea.h"
#include <QStringList>
#include <iostream>
bool NMEAFrame::isChecksumValid(QString s)
{
unsigned char checksum = 0;
int i=0;
if (s[0].latin1() != '$')
return false;
for ( i=1; i < s.length() && s[i].latin1() != '*'; i++ )
checksum ^= (unsigned char)s[i].latin1();
i++;
if (s.length() < i + 2)
return false;
bool ok;
unsigned int cmp = s.mid(i,2).toUInt(&ok, 16);
if (!ok)
return false;
//std::cout << "Checksum comparison : " << cmp << ", ref=" << (unsigned int)checksum << std::endl;
return (cmp == (unsigned int)checksum );
}
QString NMEAFrame::extractType()
{
QString head = frame.section(',',0,0);
if (head.isEmpty() || head.length() < 3)
return QString::null ;
return head.right(3);
}
NMEATime NMEAFrame::parseTime(QString s)
{
NMEATime res;
res.valid = false;
if (s.isEmpty() || s.length() != 9)
return res;
bool ok;
res.hours = s.left(2).toInt(&ok) ;
if (!ok) return res;
res.minutes = s.mid(2,2).toInt();
if (!ok) return res;
res.seconds = s.right(s.length()-4).toFloat();
if (!ok) return res;
if ( res.hours >= 0 && res.hours <= 23 &&
res.minutes >= 0 && res.minutes <= 59 &&
res.seconds >= 0 && res.seconds < 60 )
res.valid = true;
return res;
}
NMEAAngle NMEAFrame::parseAngle(QString s, QString t, int n)
{
NMEAAngle res;
res.valid = false;
/*if (s.isEmpty() || t.isEmpty() )
return res;
std::cout << "Angle data passed " << s.ascii() << t.ascii() << n << std::endl;*/
if (s.isEmpty() || t.isEmpty() || t.length() != 1) // pas de test de longueur ici sur s car != norme NMEA
return res;
if ( n == 2)
if (t != "N" && t != "S")
return res;
if ( n == 3)
if (t != "W" && t != "E")
return res;
bool ok;
res.degrees = s.left(n).toInt(&ok) ;
if (!ok) return res;
res.minutes = s.right(s.length()-n).toFloat(&ok);
if (!ok) return res;
// if ( t == "S" || t == "W" )
// {
// res.degrees = -res.degrees ;
// res.minutes = -res.minutes ;
// }
res.direction = t[0].latin1();
res.valid = true;
return res;
}
/********************************************************************
* NMEA GGA Frame
********************************************************************/
void NMEAFrameGGA::parseFrame()
{
QStringList ls = QStringList::split(',',getRawFrame(),true);
if (ls.count() != 15)
{
valid = false;
return ;
}
time = parseTime(ls[1]);
latitude = parseLatitude(ls[2],ls[3]);
longitude = parseLongitude(ls[4],ls[5]);
GPSQuality = ls[6].toInt();
SVNumber = ls[7].toInt();
DOP = ls[8].toFloat();
antennaHeight = ls[9].toFloat();
geoidSeparation = ls[11].toFloat();
valid = latitude.valid && longitude.valid && time.valid ;
return ;
}
void NMEAFrameGGA::dump()
{
//std::cout << "NMEA GGA: time, position, fix" << std::endl;
if (!valid)
{
std::cout << "\tInvalid !" << std::endl;
return ;
}
/*std::cout << "\t- time: " << time.hours << ":" << time.minutes << ":" << time.seconds << std::endl
<< "\t- lat : " << latitude.degrees <<"" << latitude.minutes << "' " << latitude.direction << std::endl
<< "\t- lon : " << longitude.degrees <<"" << longitude.minutes << "' " << longitude.direction << std::endl
<< "\t- alt : " << antennaHeight << "m" << std::endl
<< "\t- DOP,SV : " << DOP << "m, " << SVNumber << std::endl;*/
}
/********************************************************************
* NMEA GLL Frame
********************************************************************/
void NMEAFrameGLL::parseFrame()
{
QStringList ls = QStringList::split(',',getRawFrame(),true);
if (ls.count() != 8)
{
valid = false;
return ;
}
time = parseTime(ls[5]);
latitude = parseLatitude(ls[1],ls[2]);
longitude = parseLongitude(ls[3],ls[4]);
valid = latitude.valid && longitude.valid && time.valid ;
return ;
}
void NMEAFrameGLL::dump()
{
//std::cout << "NMEA GLL: time, position, fix" << std::endl;
if (!valid)
{
std::cout << "\tInvalid !" << std::endl;
return ;
}
/*std::cout << "\t- time: " << time.hours << ":" << time.minutes << ":" << time.seconds << std::endl
<< "\t- lat : " << latitude.degrees <<"" << latitude.minutes << "' " << latitude.direction << std::endl
<< "\t- lon : " << longitude.degrees <<"" << longitude.minutes << "' " << longitude.direction << std::endl;*/
}
/********************************************************************
* NMEA RMC Frame
********************************************************************/
void NMEAFrameRMC::parseFrame()
{
QStringList ls = QStringList::split(',',getRawFrame(),true);
if (ls.count() != 13)
{
valid = false;
return ;
}
time = parseTime(ls[1]);
latitude = parseLatitude(ls[3],ls[4]);
longitude = parseLongitude(ls[5],ls[6]);
speed = ls[7].toFloat();
trackAngle = ls[8].toFloat();
UTDate = ls[9].toInt();
MAGVariation = ls[10].toFloat();
MAGDir = (ls[11])[0].latin1();
valid = latitude.valid && longitude.valid && time.valid ;
return ;
}
void NMEAFrameRMC::dump()
{
//std::cout << "NMEA RMC: time, position, fix" << std::endl;
if (!valid)
{
std::cout << "\tInvalid !" << std::endl;
return ;
}
/*std::cout << "\t- time: " << time.hours << ":" << time.minutes << ":" << time.seconds << std::endl
<< "\t- lat : " << latitude.degrees <<"" << latitude.minutes << "' " << latitude.direction << std::endl
<< "\t- lon : " << longitude.degrees <<"" << longitude.minutes << "' " << longitude.direction << std::endl;*/
//!< \todo complete things here for complete dump.
}
/********************************************************************
* NMEA VTG Frame
********************************************************************/
void NMEAFrameVTG::parseFrame()
{
QStringList ls = QStringList::split(',',getRawFrame(),true);
if (ls.count() != 9)
{
return ;
}
knotSpeed = ls[5].toFloat();
kmSpeed = ls[7].toFloat();
trackAngle = ls[1].toFloat();
return ;
}
void NMEAFrameVTG::dump()
{
//std::cout << "NMEA VTG: track angle, speed over ground" << std::endl;
// std::cout << "\t- time: " << time.hours << ":" << time.minutes << ":" << time.seconds << std::endl
// << "\t- lat : " << latitude.degrees <<"" << latitude.minutes << "' " << latitude.direction << std::endl
// << "\t- lon : " << longitude.degrees <<"" << longitude.minutes << "' " << longitude.direction << std::endl;
//!< \todo complete things here for complete dump.
}
#ifndef __NMEA_H__
#define __NMEA_H__
/*! \file nmea.h
* \brief This file contains classes to handle NMEA messages
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
#include <QString>
#include <iostream>
/*! \brief A structure representing NMEA Time, which is expressed in UTC.
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
typedef struct
{
int hours; //!< hours
int minutes; //!< minutes
float seconds; //!< seconds
bool valid; //!< <tt>false</tt> if there were troubles in decoding NMEAFrame
} NMEATime ;
/*! \brief A structure representing NMEA angles, in latitude or in longitude.
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
typedef struct
{
int degrees; //!< degrees
float minutes; //!< minutes
char direction; //!< direction : should "N" or "S" if it is representing a latitude, "E" or "W" when it is a longitude.
bool valid; //!< <tt>false</tt> if there were troubles in decoding NMEAFrame
} NMEAAngle ;
/*! \brief This is typical NMEA Frame handler
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class NMEAFrame
{
public:
/*! \brief Simple constructor.
*
* This constructor can perform a checksum.
*/
NMEAFrame(QString s) { frame = s; if (isChecksumRequired()) validChecksum=isChecksumValid(s); else validChecksum=true;}
NMEAFrame(const NMEAFrame& nf) { frame = nf.frame; validChecksum = nf.validChecksum; } //!< copy constructor.
virtual ~NMEAFrame() {} //!< Default constructor.
/*! \brief Dumps the content of the frame.
*
* This is mainly for debugging purpose.
* You can override this function to check if your specific NMEA Frame parser is handling data correctly.
*/
virtual void dump() { /*std::cout << frame.ascii() << std::endl;*/ } //!< Mostly for debugging purpose.
bool isChecksumValid() { return validChecksum; }//!< Tells wether the checksum for this frame is valid or not.
QString getRawFrame() const { return frame; }//!< Returns the raw NMEA Frame in its unparsed state.
QString extractType();//!< Returns the type of the NMEA frame. This is usually a 3 letters id.
/*! \brief Tells wether the checksum is required or not for this frame.
*
* Most of NMEA Frames require checksum but not all.
* You should override this method for frames who doesn't require chechsumming.
*/
virtual bool isChecksumRequired() { return true;}
/*! \brief computes and compare checksums.
*
* A large set of NMEA Frames are embedding checksums.
* This a xor on all characters between the leading <tt>$</tt> and the trailing <tt>*</tt>
* which are both excluded.
* \param s A whole NMEA Frame
* \return <tt>true</tt> if checksum is corresponding to frame.
*/
static bool isChecksumValid(QString s);
static NMEATime parseTime(QString s); //!< Fills a NMEATime using its NMEA representation \a s.
static NMEAAngle parseLatitude(QString s,QString t) {return parseAngle(s,t,2);} //!< Fills a NMEAAngle using the NMEA representation of latitudes.
static NMEAAngle parseLongitude(QString s, QString t) {return parseAngle(s,t,3);} //!< Fills a NMEAAngle using the NMEA representation of longitudes.
protected:
virtual void parseFrame() {} //!< Classes inheriting this one can override this function to retrieve specific data.
private:
static NMEAAngle parseAngle(QString s, QString t, int nc);
QString frame;
bool validChecksum;
};
/*! \brief This is an advanced NMEAFrame decoder. It is intended to decode GGA Frames.
*
* GGA frames are expressing time, position and fix values.
* Amongst the values that can be recovered in this frame there are :
* <ul>
* <li>UTC Time (getUTCTime()) ;</li>
* <li>Latitude (getLatitude()) ;</li>
* <li>Longitude (getLongitude()) ; </li>
* <li>GPS Quality (getGPSQuality()) ; </li>
* <li>Number of Satellites in view (getSVNumber()) ; </li>
* <li>Altitude over the mean see level (getAntennaHeight()) ; </li>
* <li>Separation over the reference geoid used in WGS84 global localization system; </li>
* </ul>
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class NMEAFrameGGA : public NMEAFrame
{
public:
NMEAFrameGGA(QString s):NMEAFrame(s) { parseFrame();}
NMEAFrameGGA(const NMEAFrame& nf):NMEAFrame(nf) { parseFrame(); }
virtual ~NMEAFrameGGA() {}
virtual void dump();
NMEATime getUTCTime() const {return time; }
NMEAAngle getLatitude() const {return latitude;}
NMEAAngle getLongitude() const {return longitude;}
int getGPSQuality() const {return GPSQuality; }
int getSVNumber() const {return SVNumber; }
float getDOP() const { return DOP; }
float getAntennaHeight() const {return antennaHeight; }
float getGeoidSeparation() const { return geoidSeparation; }
bool isValid() const { return valid; } //!< This will return <tt>false</tt> if there were troubles in decoding this frame.
protected:
virtual void parseFrame();
private:
NMEATime time;
NMEAAngle latitude;
NMEAAngle longitude;
int GPSQuality;
int SVNumber;
float DOP;
float antennaHeight;
float geoidSeparation ;
bool valid;
};
/*! \brief This is an advanced NMEAFrame decoder. It is intended to decode GLL Frames.
*
* GLL frames are expressing time and position values.
* Amongst the values that can be recovered in this frame there are :
* <ul>
* <li>UTC Time (getUTCTime()) ;</li>
* <li>Latitude (getLatitude()) ;</li>
* <li>Longitude (getLongitude()) ; </li>
* </ul>
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class NMEAFrameGLL : public NMEAFrame
{
public:
NMEAFrameGLL(QString s):NMEAFrame(s) { parseFrame();}
NMEAFrameGLL(const NMEAFrame& nf):NMEAFrame(nf) { parseFrame(); }
virtual ~NMEAFrameGLL() {}
virtual void dump();
NMEATime getUTCTime() const {return time; }
NMEAAngle getLatitude() const {return latitude;}
NMEAAngle getLongitude() const {return longitude;}
bool isValid() const { return valid; } //!< This will return <tt>false</tt> if there were troubles in decoding this frame.
protected:
virtual void parseFrame();
private:
NMEATime time;
NMEAAngle latitude;
NMEAAngle longitude;
bool valid;
};
/*! \brief This is an advanced NMEAFrame decoder. It is intended to decode RMC Frames.
*
* RMC frames are expressing the recommended minimum specific GPS/TRANSIT data.
* Amongst the values that can be recovered in this frame there are :
* <ul>
* <li>UTC Time (getUTCTime()) ;</li>
* <li>Latitude (getLatitude()) ;</li>
* <li>Longitude (getLongitude()) ; </li>
* <li>Speed over ground in knots (getSpeed()) ; </li>
* <li>Track angle in degrees (getTrackAngle()); </li>
* <li>UT Date: ddmmyy (getUTDate()); </li>
* <li>Magnetic variation in degrees (getMAGVariation()); </li>
* <li>Magnetic variation direction (E or W - getMAGDir()). </li>
* </ul>
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class NMEAFrameRMC : public NMEAFrame
{
public:
NMEAFrameRMC(QString s):NMEAFrame(s) { parseFrame();}
NMEAFrameRMC(const NMEAFrame& nf):NMEAFrame(nf) { parseFrame(); }
virtual ~NMEAFrameRMC() {}
virtual void dump();
NMEATime getUTCTime() const {return time; }
NMEAAngle getLatitude() const {return latitude;}
NMEAAngle getLongitude() const {return longitude;}
float getSpeed() const { return speed; }
float getTrackAngle() const { return trackAngle; }
int getUTDate() const { return UTDate; }
float getMAGVariation() const { return MAGVariation; }
char getMAGDir() const { return MAGDir; }
bool isValid() const { return valid; } //!< This will return <tt>false</tt> if there were troubles in decoding this frame.
protected:
virtual void parseFrame();
private:
NMEATime time;
NMEAAngle latitude;
NMEAAngle longitude;
bool valid;
float speed;
float trackAngle;
int UTDate;
float MAGVariation;
char MAGDir;
};
/*! \brief This is an advanced NMEAFrame decoder. It is intended to decode VTG Frames.
*
* VTG frames are expressing the track angle as well as speed over ground.
* Amongst the values that can be recovered in this frame there are :
* <ul>
* <li>Speed over ground in knots (getKnotSpeed()) ; </li>
* <li>Speed over ground in kilometers per hour (getKMSpeed()) ; </li>
* <li>Track angle in degrees (getTrackAngle()); </li>
* </ul>
* \author Jean-Yves Didier
* \date February, the 4th, 2008.
* \ingroup gps
*/
class NMEAFrameVTG : public NMEAFrame
{
public:
NMEAFrameVTG(QString s):NMEAFrame(s) { parseFrame();}
NMEAFrameVTG(const NMEAFrame& nf):NMEAFrame(nf) { parseFrame(); }
virtual ~NMEAFrameVTG() {}
virtual void dump();
float getKnotSpeed() const { return knotSpeed; }
float getTrackAngle() const { return trackAngle; }
float getKMSpeed() const { return kmSpeed; }
protected:
virtual void parseFrame();
private:
float knotSpeed;
float kmSpeed;
float trackAngle;
};
/**! \todo Coming soon ! GSA Frame
*/
#endif //__NMEA_H__
#include "synchro.h"
#include <fstream>
using namespace std;
//eleCI ci;
//eleGPS gps;
Synchronisation::Synchronisation(QObject* parent) : QObject(parent)
{
sTimeCI = -1;
sTimeOCV = -1;
dataq = false;
datat = false;
indCI = 0;
indGPS = 0;
}
void Synchronisation::setStartTimeCI(double t)
{
cout<<t<<endl;
sTimeCI = t;
}
void Synchronisation::setStartTimeOCV(double t)
{
sTimeOCV = t;
}
void Synchronisation::setQuaternion(float *q)
{
/*ci.q[0] = q[0];
ci.q[1] = q[1];
ci.q[2] = q[2];
ci.q[3] = q[3];
dataq = true;*/
/*if(dataq && datat) {vecCI.push_back(ci); dataq=false; datat=false; emit sendNextCI();}
*/
}
void Synchronisation::setElapsedTimeCI(int t)
{
//ci.t = sTimeCI+t;
datat=true;
/*if(dataq && datat) {vecCI.push_back(ci); dataq=false; datat=false; emit sendNextCI();}*/
}
/*
void Synchronisation::setNMEAFrame(NMEAFrame f)
{
gps.fNMEA = f.getRawFrame();
gps.t=-1;
NMEATime time;
if (f.extractType() == "GGA")
{
NMEAFrameGGA frame = f;
time = frame.getUTCTime();
gps.time = time.hours*3600+time.minutes*60+time.seconds;
}
if (f.extractType() == "GLL")
{
NMEAFrameGLL frame (f);
time = frame.getUTCTime();
gps.time = time.hours*3600+time.minutes*60+time.seconds;
}
if (f.extractType() == "RMC")
{
NMEAFrameRMC frame = f;
time = frame.getUTCTime();
gps.time = time.hours*3600+time.minutes*60+time.seconds;
}
vecGPS.push_back(gps);
}
*/
void Synchronisation::setElapsedTimeOCV(int t)
{
/*
double tcam = sTimeOCV+t;
cout<<"Temps Camera :"<< tcam<<endl;
bool trouvC=false;
eleCI c ;
while ((indCI<vecCI.size())&&(trouvC))
{
c = vecCI[indCI];
if ((tcam-c.t)<0.04)
{
trouvC= true;
cout<<"Temps CI :"<<c.t<<endl;
}
else
indCI++;
}
*/
/*bool trouvG=false;
eleCI c ;
while ((indCI<vecCI.size())&&(trouvG))
{
c = vecCI[indCI];
if ((tcam-c.time)<0.04)
{
trouvG= true;
cout<<"Temps CI :"<<c.time<<endl;
}
else
indCI++;
}*/
/*if(trouvC)
emit sendQuaternion(c.q);
else
cout<<"Plus de donnes"<<endl;*/
}
#ifndef __SYNCHRO_H__
#define __SYNCHRO_H__
#include <QObject>
#include <iostream>
#include <fstream>
//#include <vector.h>
//#include "../../sources/ARCS-Components/input/tracker/gps/nmea.h"
/*typedef struct
{
double t;
float q[4];
} eleCI;
*/
/*typedef struct
{
double time;
QString fNMEA;
} eleGPS;
*/
class Synchronisation : public QObject
{
Q_OBJECT
public:
Synchronisation(QObject* parent=0);
~Synchronisation();
public
slots:
void setQuaternion(float *q);
void setStartTimeCI(double t);
void setStartTimeOCV(double t);
//void setNMEAFrame(NMEAFrame f);
void setElapsedTimeCI(int t);
void setElapsedTimeOCV(int t);
signals:
void sendQuaternion(float *q);
//void sendNMEAFrame(NMEAFrame f);
void sendToken(QString s);
void sendNextCI();
void sendNextGPS();
private:
double sTimeCI, sTimeOCV;
//std::vector <eleCI> vecCI;
//vector <eleGPS> vecGPS;
bool dataq,datat;
int indCI, indGPS;
};
#endif
#include "synsensor.h"
using namespace std;
SynSensor::SynSensor(QObject* obj) : QObject(obj)
{
sTimeCam =-1;
sTimeCI = -1;
dataq = false;
datat = false;
datatg = false;
datag = false;
indCI = 0;
indG = 0;
indCam = 0;
mode = 3; //CAM+GPS+CI
}
void SynSensor::setQuaternion(float *q)
{
ci.quat[0] = q[0];
ci.quat[1] = q[1];
ci.quat[2] = q[2];
ci.quat[3] = q[3];
dataq = true;
if(dataq && datat)
{
vecCI.push_back(ci); dataq=false; datat=false; emit sendNextCI();
}
}
void SynSensor::setElapsedTimeCI(int t)
{
ci.temps = sTimeCI + t * 0.01;
datat = true;
if(dataq && datat)
{
vecCI.push_back(ci); dataq=false; datat=false; emit sendNextCI();
}
}
void SynSensor::setElapsedTimeCam(int t)
{
double tcam = sTimeCam + t * 0.001;
//cout<<t<<endl;
//cout<<vecCI.size()<<endl;
bool trouvC = false;
bool stop = false;
while ((!trouvC) && (indCI<vecCI.size()) && (!stop))
{
eleCI c = vecCI[indCI];
if((tcam - c.temps) >= 0 && (tcam -c.temps) < 0.01)
trouvC = true;
else
{
if ((tcam - c.temps) < 0)
stop = true;
else
indCI++;
}
}
bool trouvG = false;
//cout<<vecGPS.size()<<endl;
while ((!trouvG) && (indG<vecGPS.size()) && (!stop))
{
eleGPS g = vecGPS[indG]; //cout<<indG<<" "<<g.temps<<" "<<g.p[0]<<" "<<g.p[1]<<" "<<g.p[2]<<endl;
if((tcam - g.temps)< 0.1 && (tcam -g.temps)>=0)
trouvG = true;
else
{
if ((tcam - g.temps) < 0)
stop = true;
else
indG++;
}
}
if(trouvG && trouvC && mode==3) // CAM+GPS+CI
{
cout<<fixed<<indCam<<" Temps cam "<<tcam<<" Temps GPS ("<<indG<<") "<<vecGPS[indG].temps<<" Temps CI ("<<indCI<<") "<<vecCI[indCI].temps<<endl;
CvMat *tcw, *Rcw, *p;
tcw = cvCreateMat(3,1,CV_32FC1);
Rcw = cvCreateMat(3,3,CV_32FC1);
p = cvCreateMat(3,1,CV_32FC1);
cout<<"Position:"<<endl;
cvSet1D(p,0,cvRealScalar(vecGPS[indG].p[0])); cout<<vecGPS[indG].p[0]<<" "; cvSet1D(p,1,cvRealScalar(vecGPS[indG].p[1])); cout<<vecGPS[indG].p[1]<<" "; cvSet1D(p,2,cvRealScalar(vecGPS[indG].p[2])); cout<<vecGPS[indG].p[2]<<endl;
cout<<"Rotation:"<<endl;
cvSet2D(Rcw,0,0,cvRealScalar(vecCI[indCI].R[0])); cout<<vecCI[indCI].R[0]<<" "; cvSet2D(Rcw,0,1,cvRealScalar(vecCI[indCI].R[1])); cout<<vecCI[indCI].R[1]<<" "; cvSet2D(Rcw,0,2,cvRealScalar(vecCI[indCI].R[2])); cout<<vecCI[indCI].R[2]<<endl;
cvSet2D(Rcw,1,0,cvRealScalar(vecCI[indCI].R[3])); cout<<vecCI[indCI].R[3]<<" "; cvSet2D(Rcw,1,1,cvRealScalar(vecCI[indCI].R[4])); cout<<vecCI[indCI].R[4]<<" "; cvSet2D(Rcw,1,2,cvRealScalar(vecCI[indCI].R[5])); cout<<vecCI[indCI].R[5]<<endl;
cvSet2D(Rcw,2,0,cvRealScalar(vecCI[indCI].R[6])); cout<<vecCI[indCI].R[6]<<" "; cvSet2D(Rcw,2,1,cvRealScalar(vecCI[indCI].R[7])); cout<<vecCI[indCI].R[7]<<" "; cvSet2D(Rcw,2,2,cvRealScalar(vecCI[indCI].R[8])); cout<<vecCI[indCI].R[8]<<endl;
cvMatMulAdd(Rcw, p, 0, tcw);
CvMat *zero;
zero = cvCreateMat(3,1,CV_32FC1);
cvSetZero(zero);
cvSub(zero,tcw,tcw);
CvScalar a;
cout<<"Translation:"<<endl;
a = cvGet1D(tcw,0); cout<<a.val[0]<<" "; a = cvGet1D(tcw,1); cout<<a.val[0]<<" "; a = cvGet1D(tcw,2); cout<<a.val[0]<<endl;
CvMat *R;
R = cvCreateMat(3,3,CV_32FC1);
cvTranspose(Rcw,R);
cout<<"Orientation:"<<endl;
for(int i=0;i<3;i++)
{
for(int j=0;j<3;j++)
{
a = cvGet2D(R,i,j); cout<<a.val[0]<<" ";
}
cout<<endl;
}
emit sendIndiceCamera(indCam);
emit sendPosition(p);
emit sendOrientation(R);
emit sendRotation(Rcw);
emit sendTranslation(tcw);
emit sendPose(Rcw,tcw);
indG++; indCI++;
cvReleaseMat(&tcw); cvReleaseMat(&zero); cvReleaseMat(&R); cvReleaseMat(&Rcw); cvReleaseMat(&p);
emit sendToken("end");
}
if(trouvG && mode==2) //CAM+GPS
{
cout<<fixed<<indCam<<" Temps cam "<<tcam<<" Temps GPS ("<<indG<<") "<<vecGPS[indG].temps<<endl;
CvMat *p;
p = cvCreateMat(3,1,CV_32FC1);
cout<<"Position:"<<endl;
cvSet1D(p,0,cvRealScalar(vecGPS[indG].p[0])); cout<<vecGPS[indG].p[0]<<" "; cvSet1D(p,1,cvRealScalar(vecGPS[indG].p[1])); cout<<vecGPS[indG].p[1]<<" "; cvSet1D(p,2,cvRealScalar(vecGPS[indG].p[2])); cout<<vecGPS[indG].p[2]<<endl;
emit sendIndiceCamera(indCam);
emit sendPosition(p);
indG++;
cvReleaseMat(&p);
emit sendToken("end");
}
if(trouvC && mode==1) //CAM+CI
{
cout<<fixed<<indCam<<" Temps cam "<<tcam<<" Temps CI ("<<indCI<<") "<<vecCI[indCI].temps<<endl;
CvMat *Rcw;
Rcw = cvCreateMat(3,3,CV_32FC1);
cout<<"Rotation:"<<endl;
cvSet2D(Rcw,0,0,cvRealScalar(vecCI[indCI].R[0])); cout<<vecCI[indCI].R[0]<<" "; cvSet2D(Rcw,0,1,cvRealScalar(vecCI[indCI].R[1])); cout<<vecCI[indCI].R[1]<<" "; cvSet2D(Rcw,0,2,cvRealScalar(vecCI[indCI].R[2])); cout<<vecCI[indCI].R[2]<<endl;
cvSet2D(Rcw,1,0,cvRealScalar(vecCI[indCI].R[3])); cout<<vecCI[indCI].R[3]<<" "; cvSet2D(Rcw,1,1,cvRealScalar(vecCI[indCI].R[4])); cout<<vecCI[indCI].R[4]<<" "; cvSet2D(Rcw,1,2,cvRealScalar(vecCI[indCI].R[5])); cout<<vecCI[indCI].R[5]<<endl;
cvSet2D(Rcw,2,0,cvRealScalar(vecCI[indCI].R[6])); cout<<vecCI[indCI].R[6]<<" "; cvSet2D(Rcw,2,1,cvRealScalar(vecCI[indCI].R[7])); cout<<vecCI[indCI].R[7]<<" "; cvSet2D(Rcw,2,2,cvRealScalar(vecCI[indCI].R[8])); cout<<vecCI[indCI].R[8]<<endl;
emit sendIndiceCamera(indCam);
emit sendRotation(Rcw);
indCI++;
cvReleaseMat(&Rcw);
emit sendToken("end");
}
indCam++;
emit sendNext();
}
void SynSensor::setNMEAFrame(NMEAFrame f)
{
double tgps;
eleGPS g;
bool val=false;
NMEATime t;
g.trame = f.getRawFrame();
if (f.extractType() == "GGA")
{
NMEAFrameGGA frame = f;
t = frame.getUTCTime();
g.temps = t.hours*3600+2*3600+t.minutes*60+t.seconds;
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
if(t.valid&&lon.valid && lat.valid)
val=true;
}
if (f.extractType() == "GLL")
{
NMEAFrameGLL frame (f);
t = frame.getUTCTime();
g.temps = t.hours*3600+2*3600+t.minutes*60+t.seconds;
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
if(t.valid&&lon.valid && lat.valid)
val = true;
}
if (f.extractType() == "RMC")
{
NMEAFrameRMC frame = f;
t = frame.getUTCTime();
g.temps = t.hours*3600+2*3600+t.minutes*60+t.seconds;
NMEAAngle lon = frame.getLongitude();
NMEAAngle lat = frame.getLatitude();
if (t.valid&&lon.valid && lat.valid)
val = true;
}
if (val)
{//cout<<g.temps<<endl;
//cout<<t.hours<<"h"<<t.minutes<<"m"<<t.seconds<<"s"<<endl;
vecGPS.push_back(g);
}
emit sendNextGPS();
}
void SynSensor::setStartTimeCam(double t)
{
sTimeCam =t; cout<<t<<endl;
}
void SynSensor::setTimeGPS(double t)
{
gps.temps= t;
datatg = true;
cout<<t<<endl;
if(datag && datatg)
{
vecGPS.push_back(gps); cout<<"temps "<< gps.temps<<" "<<gps.p[0]<<" "<<gps.p[1]<<" "<<gps.p[2]<<endl;datag=false; datatg=false; emit sendNextGPS();
}
}
void SynSensor::sendPosCam(CvMat *p)
{
//cvCopy(p,gps.p);
CvScalar a;
a = cvGet1D(p,0); gps.p[0] = a.val[0];
a = cvGet1D(p,1); gps.p[1] = a.val[0];
a = cvGet1D(p,2); gps.p[2] = a.val[0];
datag = true;
if(datag && datatg)
{
vecGPS.push_back(gps); cout<<"position "<< gps.temps<<" "<<gps.p[0]<<" "<<gps.p[1]<<" "<<gps.p[2]<<endl; datag=false; datatg=false; emit sendNextGPS();
}
//cvReleaseMat(&gps.p);
}
void SynSensor::setRotCam(CvMat *r)
{
//cout<<"rotation"<<endl;
// cvCopy(r,ci.R);
CvScalar a;
a = cvGet2D(r,0,0); ci.R[0] = a.val[0]; a = cvGet2D(r,0,1); ci.R[1] = a.val[0]; a = cvGet2D(r,0,2); ci.R[2] = a.val[0];
a = cvGet2D(r,1,0); ci.R[3] = a.val[0]; a = cvGet2D(r,1,1); ci.R[4] = a.val[0]; a = cvGet2D(r,1,2); ci.R[5] = a.val[0];
a = cvGet2D(r,2,0); ci.R[6] = a.val[0]; a = cvGet2D(r,2,1); ci.R[7] = a.val[0]; a = cvGet2D(r,2,2); ci.R[8] = a.val[0];
dataq = true;
if(dataq && datat)
{
vecCI.push_back(ci); dataq=false; datat=false; emit sendNextCI();
}
//cvReleaseMat(&ci.R);
}
\ No newline at end of file
#ifndef __SYNSENSOR_H__
#define __SYNSENSOR_H__
#include <QObject>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <opencv/cxcore.h>
#include <opencv/cvaux.h>
#include <vector>
#include "nmea.h"
typedef struct
{
double temps;
float quat[4];
double R[9];
} eleCI;
typedef struct
{
double temps;
QString trame;
double p[3];
} eleGPS;
class SynSensor : public QObject
{
Q_OBJECT
public :
SynSensor(QObject* parent=0) ;
public
slots :
void setStartTimeCam(double t);
void setStartTimeCI(double t){sTimeCI=t;};
void setQuaternion(float *q);
void setRotCam(CvMat *r);
void setElapsedTimeCI(int t);
void setElapsedTimeCam(int t);
void setNMEAFrame(NMEAFrame f);
void setTimeGPS(double t);
void sendPosCam(CvMat *p);
void setMode(int val){mode=val;};
signals :
void sendToken(QString s);
void sendNextCI();
void sendNextGPS();
void sendNext();
void sendQuaternion(float *q);
void sendPosition(CvMat *p);
void sendOrientation(CvMat *R);
void sendRotation(CvMat *R);
void sendTranslation(CvMat *t);
void sendIndiceCamera(int ind);
void sendPose(CvMat *r, CvMat *t);
private :
double sTimeCam, sTimeCI;
std::vector <eleCI> vecCI;
std::vector <eleGPS> vecGPS;
bool dataq, datat, datatg, datag;
eleCI ci;
eleGPS gps;
int indCI, indG, indCam, mode;
};
#endif
#include "triggps.h"
#include <iostream>
#include <QString>
GpsTrigger::GpsTrigger(QObject* parent) : QObject(parent)
{
triggered = false;
}
void GpsTrigger::setNMEAFrame(NMEAFrame data)
{
if (triggered)
{
if (data.extractType() == "GGA" || data.extractType() == "GLL" || data.extractType() == "RMC")
{ emit sendNMEAFrame(data);
triggered = false;}
}
}
#ifndef __TRIGGPS_H__
#define __TRIGGPS_H__
#include <opencv/cv.h>
#include <QObject>
#include "nmea.h"
class GpsTrigger : public QObject
{
Q_OBJECT
public:
GpsTrigger(QObject* obj=0);
public slots:
void trigger() { triggered = true;
printf("[git] trigged\n"); }
void setNMEAFrame(NMEAFrame data);
signals:
void sendNMEAFrame(NMEAFrame data);
private:
bool triggered;
};
#endif //__CVUTILS_H__