File tree Expand file tree Collapse file tree 1 file changed +6
-6
lines changed Expand file tree Collapse file tree 1 file changed +6
-6
lines changed Original file line number Diff line number Diff line change @@ -37,7 +37,7 @@ double g_covariance_orientation_z;
37
37
std::string g_frame_id;
38
38
std::string g_tf_child_frame_id;
39
39
40
- tf::TransformBroadcaster *tf_broadcaster ;
40
+ std::shared_ptr< tf::TransformBroadcaster> p_tf_broadcaster ;
41
41
42
42
void imu_callback (const sensor_msgs::ImuConstPtr& msg)
43
43
{
@@ -160,10 +160,10 @@ void gps_callback(const sensor_msgs::NavSatFixConstPtr& msg)
160
160
g_latest_imu_msg.orientation .y ,
161
161
g_latest_imu_msg.orientation .z ,
162
162
g_latest_imu_msg.orientation .w ));
163
- tf_broadcaster ->sendTransform (tf::StampedTransform (transform,
164
- ros::Time::now (),
165
- g_frame_id,
166
- g_tf_child_frame_id));
163
+ p_tf_broadcaster ->sendTransform (tf::StampedTransform (transform,
164
+ ros::Time::now (),
165
+ g_frame_id,
166
+ g_tf_child_frame_id));
167
167
}
168
168
169
169
int main (int argc, char **argv) {
@@ -173,7 +173,7 @@ int main(int argc, char **argv) {
173
173
174
174
g_got_imu = false ;
175
175
g_got_altitude = false ;
176
- tf_broadcaster = new tf::TransformBroadcaster ();
176
+ p_tf_broadcaster = std::make_shared< tf::TransformBroadcaster> ();
177
177
178
178
// Use different coordinate transform if using simulator
179
179
if (!pnh.getParam (" is_sim" , g_is_sim)) {
You can’t perform that action at this time.
0 commit comments