Skip to content

Commit a5f09cd

Browse files
committed
fixed compilation errors
1 parent 05456ff commit a5f09cd

File tree

2 files changed

+9
-1
lines changed

2 files changed

+9
-1
lines changed

Software/real_time/ROS_RoboBuggy/src/robobuggy/include/transistor/gps/GPS_Broadcaster.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,8 @@
88
#include "ros/ros.h"
99
#include "robobuggy/GPS.h"
1010
#include "serial/serial.h"
11+
#include <geographic_msgs/GeoPoint.h>
12+
#include <geodesy/utm.h>
1113

1214
#include <sstream>
1315

@@ -30,6 +32,7 @@ class GPS_Broadcaster
3032
std::string serial_port;
3133
int serial_baud;
3234
std::string gps_serial_buffer;
35+
serial::Serial gps_serial;
3336

3437
double convert_to_latitude(std::string str);
3538
double convert_to_longitude(std::string str);

Software/real_time/ROS_RoboBuggy/src/robobuggy/src/transistor/gps/GPS_Broadcaster.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,12 @@ GPS_Broadcaster::GPS_Broadcaster()
1818
serial_baud = 9600;
1919
}
2020

21+
22+
23+
}
24+
25+
void GPS_Broadcaster::initialize_hardware()
26+
{
2127
try
2228
{
2329
gps_serial.setPort(serial_port);
@@ -31,7 +37,6 @@ GPS_Broadcaster::GPS_Broadcaster()
3137
ROS_ERROR_STREAM("Unable to open port");
3238
ROS_ERROR_STREAM(serial_port);
3339
}
34-
3540
}
3641

3742
//parse ONE NMEA string

0 commit comments

Comments
 (0)