asterx1_driver.cpp
Go to the documentation of this file.
00001 #include "asterx1_driver.h"
00002 
00003 Asterx1Driver::Asterx1Driver()
00004 {
00005         //setDriverId(driver string id);
00006   
00007         gpsDevice = new CasteRx1("/dev/ttyACM0", MSEC500);
00008 }
00009 
00010 bool Asterx1Driver::openDriver(void)
00011 {
00012   //setDriverId(driver string id);
00013 
00014         if ( gpsDevice->openDevice(5) == BASIC_SUCCESS )
00015         {
00016                 return true;
00017         }
00018         else
00019         {
00020                 return false;
00021         }
00022 }
00023 
00024 bool Asterx1Driver::closeDriver(void)
00025 {
00026         if ( gpsDevice->closeDevice() == BASIC_SUCCESS )
00027         {
00028                 return true;
00029         }
00030         else
00031         {
00032                 return false;
00033         }
00034 }
00035 
00036 bool Asterx1Driver::startDriver(void)
00037 {
00038         if ( gpsDevice->startAcquisition() == BASIC_SUCCESS )
00039         {
00040                 return true;
00041         }
00042         else
00043         {
00044                 return false;
00045         }
00046 }
00047 
00048 bool Asterx1Driver::stopDriver(void)
00049 {
00050         if ( gpsDevice->stopAcquisition() == BASIC_SUCCESS )
00051         {
00052                 return true;
00053         }
00054         else
00055         {
00056                 return false;
00057         }
00058 }
00059 
00060 void Asterx1Driver::config_update(const Config& new_cfg, uint32_t level)
00061 {
00062         this->lock();
00063   
00064   //update driver with new_cfg data
00065         try
00066         {
00067                 if( this->getState() == Asterx1Driver::CLOSED )
00068                 {
00069                         this->gpsDevice->setPortName(new_cfg.serialPortName);
00070                         this->gpsDevice->setMapOrigin(new_cfg.mapOriginLat,new_cfg.mapOriginLon,new_cfg.mapOriginAlt,new_cfg.mapOriginYaw);
00071                 }
00072                 if( (this->getState() != Asterx1Driver::RUNNING) )
00073                 {
00074                         this->gpsDevice->setAcquisitionRate(new_cfg.acquisitionRate);
00075                 }
00076         }
00077         catch(CException &e)
00078         {
00079                 ROS_ERROR("'%s'", e.what().c_str());
00080         }
00081 
00082   // save the current configuration
00083         this->config_=new_cfg;
00084 
00085         this->unlock();
00086 }
00087 
00088 Asterx1Driver::~Asterx1Driver()
00089 {
00090         delete gpsDevice;
00091 }
00092 
00093 void Asterx1Driver::setMapOrigin(double mapLat0, double mapLon0, double mapAlt0, double mapAlpha0)
00094 {
00095         gpsDevice->setMapOrigin(mapLat0, mapLon0, mapAlt0, mapAlpha0);
00096 }
00097 
00098 void Asterx1Driver::printTM()
00099 {
00100         gpsDevice->printTM();
00101 }
00102 
00103 int Asterx1Driver::readDataFromDevice()
00104 {
00105         return gpsDevice->readDataFromDevice();
00106 }
00107 
00108 unsigned int Asterx1Driver::getStatus(){ return gpsDevice->getStatus();}
00109 double Asterx1Driver::getTimeStamp(){ return gpsDevice->getTimeStamp();}
00110 unsigned short int Asterx1Driver::getWnc(){ return gpsDevice->getWnc();}
00111 unsigned int Asterx1Driver::getTow(){ return gpsDevice->getTow();}
00112 unsigned int Asterx1Driver::getNumSatellites(){ return gpsDevice->getNumSatellites();}
00113 float Asterx1Driver::getPDOP(){ return gpsDevice->getPDOP();}
00114 float Asterx1Driver::getTDOP(){ return gpsDevice->getTDOP();}
00115 float Asterx1Driver::getHDOP(){ return gpsDevice->getHDOP();}
00116 float Asterx1Driver::getVDOP(){ return gpsDevice->getVDOP();}
00117 float Asterx1Driver::getUndulation(){ return gpsDevice->getUndulation();}
00118 unsigned short int Asterx1Driver::getPVTerror(){ return gpsDevice->getPVTerror();}
00119 double Asterx1Driver::getLat(bool units){ return gpsDevice->getLat(units);} 
00120 double Asterx1Driver::getLon(bool units){ return gpsDevice->getLon(units);} 
00121 double Asterx1Driver::getAlt(){ return gpsDevice->getAlt();}
00122 double Asterx1Driver::getXWgs(){ return gpsDevice->getXWgs();}
00123 double Asterx1Driver::getYWgs(){ return gpsDevice->getYWgs();}
00124 double Asterx1Driver::getZWgs(){ return gpsDevice->getZWgs();}
00125 double Asterx1Driver::getXMap(){ return gpsDevice->getXMap();}
00126 double Asterx1Driver::getYMap(){ return gpsDevice->getYMap();}
00127 double Asterx1Driver::getZMap(){ return gpsDevice->getZMap();}
00128 double Asterx1Driver::getVxWgs(){ return gpsDevice->getVxWgs();}
00129 double Asterx1Driver::getVyWgs(){ return gpsDevice->getVyWgs();}
00130 double Asterx1Driver::getVzWgs(){ return gpsDevice->getVzWgs();}
00131 double Asterx1Driver::getVxMap(){ return gpsDevice->getVxMap();}
00132 double Asterx1Driver::getVyMap(){ return gpsDevice->getVyMap();}
00133 double Asterx1Driver::getVzMap(){ return gpsDevice->getVzMap();}
00134 double Asterx1Driver::getCxxWgs(){ return gpsDevice->getCxxWgs();}
00135 double Asterx1Driver::getCyyWgs(){ return gpsDevice->getCyyWgs();}
00136 double Asterx1Driver::getCzzWgs(){ return gpsDevice->getCzzWgs();}
00137 double Asterx1Driver::getCxyWgs(){ return gpsDevice->getCxyWgs();}
00138 double Asterx1Driver::getCxxMap(){ return gpsDevice->getCxxMap();}
00139 double Asterx1Driver::getCyyMap(){ return gpsDevice->getCyyMap();}
00140 double Asterx1Driver::getCzzMap(){ return gpsDevice->getCzzMap();}
00141 double Asterx1Driver::getCxyMap(){ return gpsDevice->getCxyMap();}
00142 double Asterx1Driver::getCxxEnu(){ return gpsDevice->getCxxEnu();}
00143 double Asterx1Driver::getCyyEnu(){ return gpsDevice->getCyyEnu();}
00144 double Asterx1Driver::getCzzEnu(){ return gpsDevice->getCzzEnu();}
00145 double Asterx1Driver::getCxyEnu(){ return gpsDevice->getCxyEnu();}
00146 double Asterx1Driver::getCxzEnu(){ return gpsDevice->getCxzEnu();}
00147 double Asterx1Driver::getCyzEnu(){ return gpsDevice->getCyzEnu();}


iri_asterx1
Author(s): andreu, acorominas@iri.upc.edu
autogenerated on Fri Dec 6 2013 22:38:17