GPS.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 /*---------------------------------------------------------------
11  APPLICATION: mrpt_ros bridge
12  FILE: GPS.cpp
13  AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
14  ---------------------------------------------------------------*/
15 
16 #include "mrpt_bridge/GPS.h"
17 
18 
19 namespace mrpt_bridge
20 {
21  /************************************************************************
22  * ros2mrpt *
23  ************************************************************************/
24  bool GPS::ros2mrpt(const sensor_msgs::NavSatFix &msg,
25  CObservationGPS &obj)
26  {
27  mrpt::obs::gnss::Message_NMEA_GGA gga;
28  gga.fields.altitude_meters = msg.altitude;
29  gga.fields.latitude_degrees = msg.latitude;
30  gga.fields.longitude_degrees = msg.longitude;
31 
32  switch(msg.status.status)
33  {
34  case -1:
35  gga.fields.fix_quality = 0;
36  break;
37  case 0:
38  gga.fields.fix_quality = 1;
39  break;
40  case 2:
41  gga.fields.fix_quality = 2;
42  break;
43  case 1:
44  gga.fields.fix_quality = 3;
45  break;
46  default:
47  gga.fields.fix_quality = 0; // never going to execute default
48 
49  }
50  obj.setMsg(gga);
51  return true;
52  }
53 
54  /************************************************************************
55  * mrpt2ros *
56  ************************************************************************/
57  bool GPS::mrpt2ros(const CObservationGPS &obj,
58  const std_msgs::Header &msg_header,
59  sensor_msgs::NavSatFix &msg)
60  {
61  // 1) sensor_msgs::NavSatFix:: header
62  msg.header = msg_header;
63 
64  // 2) other NavSatFix Parameters, the following 3 could be wrong too
65 
66  if (obj.hasMsgClass<mrpt::obs::gnss::Message_NMEA_GGA>())
67  {
68  const mrpt::obs::gnss::Message_NMEA_GGA &gga =
69  obj.getMsgByClass<mrpt::obs::gnss::Message_NMEA_GGA>();
70  msg.altitude = gga.fields.altitude_meters;
71  msg.latitude = gga.fields.latitude_degrees;
72  msg.longitude = gga.fields.longitude_degrees;
73 
76  switch(gga.fields.fix_quality)
77  {
78  case 0:
79  msg.status.status = -1;
80  break;
81  case 1:
82  msg.status.status = 0;
83  break;
84  case 2:
85  msg.status.status = 2;
86  break;
87  case 3:
88  msg.status.status = 1;
89  break;
90  default:
91  // this is based on literature available on GPS as the number of types in ROS and MRPT are not same
92  msg.status.status = 0;
93  }
94  // this might be incorrect as there is not matching field in mrpt message type
95  msg.status.service = 1;
96 
97  }
100  return true;
101  }
102 }
103 
104 
106 /*
107 uint8 COVARIANCE_TYPE_UNKNOWN=0
108 uint8 COVARIANCE_TYPE_APPROXIMATED=1
109 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
110 uint8 COVARIANCE_TYPE_KNOWN=3
111 std_msgs/Header header
112 sensor_msgs/NavSatStatus status
113 float64 latitude
114 float64 longitude
115 float64 altitude
116 float64[9] position_covariance
117 uint8 position_covariance_type
118 */
119 
121 /*
122 int8 STATUS_NO_FIX=-1
123 int8 STATUS_FIX=0
124 int8 STATUS_SBAS_FIX=1
125 int8 STATUS_GBAS_FIX=2
126 uint16 SERVICE_GPS=1
127 uint16 SERVICE_GLONASS=2
128 uint16 SERVICE_COMPASS=4
129 uint16 SERVICE_GALILEO=8
130 int8 status
131 uint16 service
132  */
bool mrpt2ros(const CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Definition: GPS.cpp:57
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool ros2mrpt(const sensor_msgs::NavSatFix &msg, CObservationGPS &obj)
Definition: GPS.cpp:24


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17