Skip to content

Commit f79b70b

Browse files
committed
add debug info
1 parent 8f90b95 commit f79b70b

File tree

1 file changed

+4
-2
lines changed

1 file changed

+4
-2
lines changed

src/frame_publisher.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
* Author: Sofie Nilsson
4040
* Author: Thomas Lindemeier
4141
*/
42-
42+
4343
#include <pointcloud_to_laserscan/frame_publisher.h>
4444

4545
FramePublisher::FramePublisher() :
@@ -72,14 +72,15 @@ bool FramePublisher::initialize()
7272
return true;
7373
}
7474

75-
/// Broadcast a frame aligned with the base frame but rotated around specified axes as rotation_frame
75+
/// Broadcast a new frame based on a given transformation from_frame -> to_frame - resetting either translation and/or individual rotation axes to zero
7676
void FramePublisher::frameBroadcastCallback(const ros::TimerEvent& event)
7777
{
7878
ros::Time time = event.current_real;
7979
geometry_msgs::TransformStamped transform_msg;
8080
try
8181
{
8282
transform_msg = tf_buffer_.lookupTransform(from_frame_, to_frame_, time, ros::Duration(0.1));
83+
ROS_DEBUG_STREAM("FramePublisher::frameBroadcastCallback: transform_msg:\n" << transform_msg);
8384
}
8485
catch (tf2::TransformException& ex)
8586
{
@@ -108,4 +109,5 @@ void FramePublisher::frameBroadcastCallback(const ros::TimerEvent& event)
108109
geometry_msgs::TransformStamped published_msg = tf2::toMsg(published_tf);
109110
published_msg.child_frame_id = frame_name_;
110111
tf_broadcaster_.sendTransform(published_msg);
112+
ROS_DEBUG_STREAM("FramePublisher::frameBroadcastCallback: published_msg:\n" << published_msg);
111113
}

0 commit comments

Comments
 (0)