Skip to content

Commit 06793e4

Browse files
author
marija-p
committed
Add parameter to publish GPS pose or not
Reformat using Clang
1 parent 1a15074 commit 06793e4

File tree

1 file changed

+40
-21
lines changed

1 file changed

+40
-21
lines changed

src/gps_to_pose_conversion_node.cpp

Lines changed: 40 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include <std_msgs/Float64.h>
1515

1616
bool g_is_sim;
17+
bool g_publish_pose;
1718

1819
geodetic_converter::GeodeticConverter g_geodetic_converter;
1920
sensor_msgs::Imu g_latest_imu_msg;
@@ -126,11 +127,14 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
126127
}
127128
}
128129

129-
g_gps_pose_pub.publish(pose_msg);
130+
if (g_publish_pose) {
131+
g_gps_pose_pub.publish(pose_msg);
132+
}
130133
g_gps_position_pub.publish(position_msg);
131134

132135
// Fill up transform message
133-
geometry_msgs::TransformStampedPtr transform_msg(new geometry_msgs::TransformStamped);
136+
geometry_msgs::TransformStampedPtr transform_msg(
137+
new geometry_msgs::TransformStamped);
134138
transform_msg->header = msg->header;
135139
transform_msg->header.frame_id = "world";
136140
transform_msg->transform.translation.x = x;
@@ -145,8 +149,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
145149
g_gps_transform_pub.publish(transform_msg);
146150
}
147151

148-
int main(int argc, char** argv)
149-
{
152+
int main(int argc, char **argv) {
150153
ros::init(argc, argv, "gps_to_pose_conversion_node");
151154
ros::NodeHandle nh;
152155
ros::NodeHandle pnh("~");
@@ -166,41 +169,57 @@ int main(int argc, char** argv)
166169
ros::param::param("~trust_gps", g_trust_gps, false);
167170

168171
// Get manual parameters
169-
ros::param::param("~fixed_covariance/position/x", g_covariance_position_x, 4.0);
170-
ros::param::param("~fixed_covariance/position/y", g_covariance_position_y, 4.0);
171-
ros::param::param("~fixed_covariance/position/z", g_covariance_position_z, 100.0);
172-
ros::param::param("~fixed_covariance/orientation/x", g_covariance_orientation_x, 0.02);
173-
ros::param::param("~fixed_covariance/orientation/y", g_covariance_orientation_y, 0.02);
174-
ros::param::param("~fixed_covariance/orientation/z", g_covariance_orientation_z, 0.11);
172+
ros::param::param("~fixed_covariance/position/x", g_covariance_position_x,
173+
4.0);
174+
ros::param::param("~fixed_covariance/position/y", g_covariance_position_y,
175+
4.0);
176+
ros::param::param("~fixed_covariance/position/z", g_covariance_position_z,
177+
100.0);
178+
ros::param::param("~fixed_covariance/orientation/x",
179+
g_covariance_orientation_x, 0.02);
180+
ros::param::param("~fixed_covariance/orientation/y",
181+
g_covariance_orientation_y, 0.02);
182+
ros::param::param("~fixed_covariance/orientation/z",
183+
g_covariance_orientation_z, 0.11);
184+
185+
// Specify whether to publish pose or not
186+
ros::param::param("~publish_pose", g_publish_pose, false);
175187

176188
// Wait until GPS reference parameters are initialized.
177189
double latitude, longitude, altitude;
178190
do {
179191
ROS_INFO("Waiting for GPS reference parameters...");
180-
if (nh.getParam("/gps_ref_latitude", latitude) && nh.getParam("/gps_ref_longitude", longitude)
181-
&& nh.getParam("/gps_ref_altitude", altitude)) {
192+
if (nh.getParam("/gps_ref_latitude", latitude) &&
193+
nh.getParam("/gps_ref_longitude", longitude) &&
194+
nh.getParam("/gps_ref_altitude", altitude)) {
182195
g_geodetic_converter.initialiseReference(latitude, longitude, altitude);
183196
} else {
184-
ROS_INFO("GPS reference not ready yet, use set_gps_reference_node to set it");
185-
ros::Duration(0.5).sleep(); // sleep for half a second
197+
ROS_INFO(
198+
"GPS reference not ready yet, use set_gps_reference_node to set it");
199+
ros::Duration(0.5).sleep(); // sleep for half a second
186200
}
187201
} while (!g_geodetic_converter.isInitialised());
188202

189203
// Show reference point
190204
double initial_latitude, initial_longitude, initial_altitude;
191-
g_geodetic_converter.getReference(&initial_latitude, &initial_longitude, &initial_altitude);
192-
ROS_INFO("GPS reference initialized correctly %f, %f, %f", initial_latitude, initial_longitude,
193-
initial_altitude);
205+
g_geodetic_converter.getReference(&initial_latitude, &initial_longitude,
206+
&initial_altitude);
207+
ROS_INFO("GPS reference initialized correctly %f, %f, %f", initial_latitude,
208+
initial_longitude, initial_altitude);
194209

195210
// Initialize publishers
196-
g_gps_pose_pub = nh.advertise < geometry_msgs::PoseWithCovarianceStamped > ("gps_pose", 1);
197-
g_gps_transform_pub = nh.advertise < geometry_msgs::TransformStamped > ("gps_transform", 1);
198-
g_gps_position_pub = nh.advertise < geometry_msgs::PointStamped > ("gps_position", 1);
211+
g_gps_pose_pub =
212+
nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("gps_pose", 1);
213+
g_gps_transform_pub =
214+
nh.advertise<geometry_msgs::TransformStamped>("gps_transform", 1);
215+
g_gps_position_pub =
216+
nh.advertise<geometry_msgs::PointStamped>("gps_position", 1);
199217

200218
// Subscribe to IMU and GPS fixes, and convert in GPS callback
201219
ros::Subscriber imu_sub = nh.subscribe("imu", 1, &imu_callback);
202220
ros::Subscriber gps_sub = nh.subscribe("gps", 1, &gps_callback);
203-
ros::Subscriber altitude_sub = nh.subscribe("external_altitude", 1, &altitude_callback);
221+
ros::Subscriber altitude_sub =
222+
nh.subscribe("external_altitude", 1, &altitude_callback);
204223

205224
ros::spin();
206225
}

0 commit comments

Comments
 (0)