Skip to content

Commit a211d23

Browse files
committed
add changes based on PR #21 review
1 parent e75078d commit a211d23

File tree

2 files changed

+8
-11
lines changed

2 files changed

+8
-11
lines changed

CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@ cs_add_executable(set_gps_reference_node src/set_gps_reference_node.cpp)
1313
target_link_libraries(set_gps_reference_node ${catkin_LIBRARIES})
1414

1515
cs_add_executable(gps_to_pose_conversion_node src/gps_to_pose_conversion_node.cpp)
16-
target_link_libraries(gps_to_pose_conversion_node ${catkin_LIBRARIES})
16+
#target_link_libraries(gps_to_pose_conversion_node ${catkin_LIBRARIES})
1717

1818
cs_install()
19-
cs_install_scripts(src/gps_spoofer.py src/euler_radians_to_degrees.py src/odometry_height_adjuster.py)
19+
cs_install_scripts(src/gps_spoofer.py src/euler_radians_to_degrees.py)
2020
cs_export()

src/set_gps_reference_node.cpp

Lines changed: 6 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,8 @@
77
double g_lat_ref;
88
double g_lon_ref;
99
double g_alt_ref;
10-
int count = 1;
10+
int g_count = 1;
1111
bool gps_ref_is_init;
12-
13-
std::vector<double> g_pressure_heights;
1412
int g_its;
1513

1614
enum EMode
@@ -23,7 +21,7 @@ EMode g_mode;
2321

2422
bool reset_callback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
2523
{
26-
count = 1;
24+
g_count = 1;
2725
g_lat_ref = 0.0;
2826
g_lon_ref = 0.0;
2927
g_alt_ref = 0.0;
@@ -36,7 +34,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr & msg)
3634
{
3735
ros::NodeHandle nh;
3836
nh.getParam("/gps_ref_is_init", gps_ref_is_init);
39-
37+
4038
if (!gps_ref_is_init){
4139

4240

@@ -51,7 +49,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr & msg)
5149

5250
ROS_INFO("Current measurement: %f, %f, %f", msg->latitude, msg->longitude, msg->altitude);
5351

54-
if (count == g_its) {
52+
if (g_count == g_its) {
5553
if (g_mode == MODE_AVERAGE) {
5654
g_lat_ref /= g_its;
5755
g_lon_ref /= g_its;
@@ -70,13 +68,12 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr & msg)
7068

7169
ROS_INFO("Final reference position: %f, %f, %f", g_lat_ref, g_lon_ref, g_alt_ref);
7270

73-
//ros::shutdown();
7471
return;
7572
} else {
76-
ROS_INFO(" Still waiting for %d measurements", g_its - count);
73+
ROS_INFO(" Still waiting for %d measurements", g_its - g_count);
7774
}
7875

79-
count++;
76+
g_count++;
8077
}
8178
}
8279

0 commit comments

Comments
 (0)