File tree Expand file tree Collapse file tree 2 files changed +9
-1
lines changed
Software/real_time/ROS_RoboBuggy/src/robobuggy Expand file tree Collapse file tree 2 files changed +9
-1
lines changed Original file line number Diff line number Diff line change 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);
Original file line number Diff line number Diff 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
You can’t perform that action at this time.
0 commit comments