Skip to content

Commit 548d5eb

Browse files
author
marco-tranzatto
committed
frame_id string in header section of output messages can be set as rosparam now and it's not hardcoded anymore
1 parent ad0cdfb commit 548d5eb

File tree

1 file changed

+6
-3
lines changed

1 file changed

+6
-3
lines changed

src/gps_to_pose_conversion_node.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ double g_covariance_position_z;
3333
double g_covariance_orientation_x;
3434
double g_covariance_orientation_y;
3535
double g_covariance_orientation_z;
36+
std::string g_frame_id;
3637

3738
void imu_callback(const sensor_msgs::ImuConstPtr& msg)
3839
{
@@ -79,7 +80,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
7980
geometry_msgs::PoseWithCovarianceStampedPtr pose_msg(
8081
new geometry_msgs::PoseWithCovarianceStamped);
8182
pose_msg->header = msg->header;
82-
pose_msg->header.frame_id = "world";
83+
pose_msg->header.frame_id = g_frame_id;
8384
pose_msg->pose.pose.position.x = x;
8485
pose_msg->pose.pose.position.y = y;
8586
pose_msg->pose.pose.position.z = z;
@@ -89,7 +90,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
8990
geometry_msgs::PointStampedPtr position_msg(
9091
new geometry_msgs::PointStamped);
9192
position_msg->header = pose_msg->header;
92-
position_msg->header.frame_id = "world";
93+
position_msg->header.frame_id = g_frame_id;
9394
position_msg->point = pose_msg->pose.pose.position;
9495

9596
// If external altitude messages received, include in pose and position messages
@@ -136,7 +137,7 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
136137
geometry_msgs::TransformStampedPtr transform_msg(
137138
new geometry_msgs::TransformStamped);
138139
transform_msg->header = msg->header;
139-
transform_msg->header.frame_id = "world";
140+
transform_msg->header.frame_id = g_frame_id;
140141
transform_msg->transform.translation.x = x;
141142
transform_msg->transform.translation.y = y;
142143
transform_msg->transform.translation.z = z;
@@ -181,6 +182,8 @@ int main(int argc, char **argv) {
181182
g_covariance_orientation_y, 0.02);
182183
ros::param::param("~fixed_covariance/orientation/z",
183184
g_covariance_orientation_z, 0.11);
185+
ros::param::param<std::string>("~frame_id",
186+
g_frame_id, "world");
184187

185188
// Specify whether to publish pose or not
186189
ros::param::param("~publish_pose", g_publish_pose, false);

0 commit comments

Comments
 (0)