GPS.cpp
Go to the documentation of this file.
00001 /* +------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)            |
00003    |                          http://www.mrpt.org/                          |
00004    |                                                                        |
00005    | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file     |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                |
00007    | Released under BSD License. See details in http://www.mrpt.org/License |
00008    +------------------------------------------------------------------------+ */
00009 
00010 /*---------------------------------------------------------------
00011         APPLICATION: mrpt_ros bridge
00012         FILE: GPS.cpp
00013         AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
00014   ---------------------------------------------------------------*/
00015 
00016 #include "mrpt_bridge/GPS.h"
00017 
00018 
00019 namespace mrpt_bridge
00020 {
00021     /************************************************************************
00022     *                                           ros2mrpt                                                                *
00023     ************************************************************************/
00024     bool GPS::ros2mrpt(const sensor_msgs::NavSatFix &msg,
00025                   CObservationGPS &obj)
00026     {
00027         mrpt::obs::gnss::Message_NMEA_GGA gga;
00028         gga.fields.altitude_meters      = msg.altitude;
00029         gga.fields.latitude_degrees     = msg.latitude;
00030         gga.fields.longitude_degrees    = msg.longitude;
00031 
00032         switch(msg.status.status)
00033         {
00034             case -1:
00035                 gga.fields.fix_quality  = 0;
00036                 break;
00037             case 0:
00038                 gga.fields.fix_quality  = 1;
00039                 break;
00040             case 2:
00041                 gga.fields.fix_quality  = 2;
00042                 break;
00043             case 1:
00044                 gga.fields.fix_quality  = 3;
00045                 break;
00046             default:
00047                 gga.fields.fix_quality  = 0; // never going to execute default
00048 
00049         }
00050         obj.setMsg(gga);
00051         return true;
00052     }
00053 
00054     /************************************************************************
00055     *                                           mrpt2ros                                                                *
00056     ************************************************************************/
00057     bool GPS::mrpt2ros(const CObservationGPS &obj,
00058                   const std_msgs::Header &msg_header,
00059                   sensor_msgs::NavSatFix &msg)
00060     {
00061         // 1) sensor_msgs::NavSatFix:: header
00062         msg.header = msg_header;
00063 
00064         // 2) other NavSatFix Parameters, the following 3 could be wrong too
00065 
00066         if (obj.hasMsgClass<mrpt::obs::gnss::Message_NMEA_GGA>())
00067         {
00068             const mrpt::obs::gnss::Message_NMEA_GGA &gga =
00069                     obj.getMsgByClass<mrpt::obs::gnss::Message_NMEA_GGA>();
00070             msg.altitude    = gga.fields.altitude_meters;
00071             msg.latitude    = gga.fields.latitude_degrees;
00072             msg.longitude   = gga.fields.longitude_degrees;
00073 
00076             switch(gga.fields.fix_quality)
00077             {
00078                 case 0:
00079                     msg.status.status = -1;
00080                     break;
00081                 case 1:
00082                     msg.status.status = 0;
00083                     break;
00084                 case 2:
00085                     msg.status.status = 2;
00086                     break;
00087                 case 3:
00088                     msg.status.status = 1;
00089                     break;
00090                 default:
00091                     // this is based on literature available on GPS as the number of types in ROS and MRPT are not same
00092                     msg.status.status = 0;
00093             }
00094             // this might be incorrect as there is not matching field in mrpt message type
00095             msg.status.service = 1;
00096 
00097         }
00100         return true;
00101     }
00102 }
00103 
00104 
00106 /*
00107 uint8 COVARIANCE_TYPE_UNKNOWN=0
00108 uint8 COVARIANCE_TYPE_APPROXIMATED=1
00109 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
00110 uint8 COVARIANCE_TYPE_KNOWN=3
00111 std_msgs/Header header
00112 sensor_msgs/NavSatStatus status
00113 float64 latitude
00114 float64 longitude
00115 float64 altitude
00116 float64[9] position_covariance
00117 uint8 position_covariance_type
00118 */
00119 
00121 /*
00122 int8 STATUS_NO_FIX=-1
00123 int8 STATUS_FIX=0
00124 int8 STATUS_SBAS_FIX=1
00125 int8 STATUS_GBAS_FIX=2
00126 uint16 SERVICE_GPS=1
00127 uint16 SERVICE_GLONASS=2
00128 uint16 SERVICE_COMPASS=4
00129 uint16 SERVICE_GALILEO=8
00130 int8 status
00131 uint16 service
00132  */


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Apr 27 2018 05:10:54