Skip to content

Commit 8f90b95

Browse files
committed
combine and harmonize functionality
1 parent bd35056 commit 8f90b95

File tree

7 files changed

+35
-295
lines changed

7 files changed

+35
-295
lines changed

CMakeLists.txt

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,6 @@ target_link_libraries(frame_publisher ${catkin_LIBRARIES})
3131
add_executable(frame_publisher_node src/frame_publisher_node.cpp)
3232
target_link_libraries(frame_publisher_node frame_publisher ${catkin_LIBRARIES})
3333

34-
add_library(fixable_rotation_frame_publisher src/fixable_rotation_frame_publisher.cpp)
35-
target_link_libraries(fixable_rotation_frame_publisher ${catkin_LIBRARIES})
36-
37-
add_executable(fixable_rotation_frame_publisher_node src/fixable_rotation_frame_publisher_node.cpp)
38-
target_link_libraries(fixable_rotation_frame_publisher_node fixable_rotation_frame_publisher ${catkin_LIBRARIES})
39-
4034
add_library(roi_outlier_removal src/roi_outlier_removal_nodelet.cpp)
4135
target_link_libraries(roi_outlier_removal ${catkin_LIBRARIES})
4236

include/pointcloud_to_laserscan/fixable_rotation_frame_publisher.h

Lines changed: 0 additions & 81 deletions
This file was deleted.

include/pointcloud_to_laserscan/frame_publisher.h

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636

3737
/*
3838
* Author: Sofie Nilsson
39+
* Author: Thomas Lindemeier
3940
*/
4041

4142
#ifndef FRAME_PUB_H
@@ -70,9 +71,10 @@ class FramePublisher
7071

7172
ros::Timer frame_broadcast_timer_;
7273
double update_rate_;
73-
std::string base_frame_;
74-
std::string rotation_frame_;
75-
std::string target_frame_;
74+
std::string from_frame_;
75+
std::string to_frame_;
76+
std::string frame_name_;
77+
bool use_to_frame_translation_;
7678
bool rot_z_, rot_x_, rot_y_;
7779
};
7880

src/fixable_rotation_frame_publisher.cpp

Lines changed: 0 additions & 120 deletions
This file was deleted.

src/fixable_rotation_frame_publisher_node.cpp

Lines changed: 0 additions & 58 deletions
This file was deleted.

src/frame_publisher.cpp

Lines changed: 26 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737

3838
/*
3939
* Author: Sofie Nilsson
40+
* Author: Thomas Lindemeier
4041
*/
4142

4243
#include <pointcloud_to_laserscan/frame_publisher.h>
@@ -52,58 +53,59 @@ bool FramePublisher::initialize()
5253
{
5354
priv_nh_ = ros::NodeHandle("~");
5455

55-
priv_nh_.param<double>("update_rate", update_rate_, 0.01); // 100Hz
56+
priv_nh_.param<double>("update_rate", update_rate_, 0.01); // 100Hz
5657

57-
priv_nh_.param<std::string>("base_frame", base_frame_, "base_link");
58-
priv_nh_.param<std::string>("rotation_frame", rotation_frame_, "torso_center_link");
59-
priv_nh_.param<std::string>("target_frame", target_frame_, "torso_rotated_base_link");
58+
priv_nh_.param<std::string>("from_frame", from_frame_, "base_link");
59+
priv_nh_.param<std::string>("to_frame", to_frame_, "torso_center_link");
60+
priv_nh_.param<std::string>("frame_name", frame_name_, "torso_rotated_base_link");
61+
62+
priv_nh_.param<bool>("use_to_frame_translation", use_to_frame_translation_, true);
6063

6164
priv_nh_.param<bool>("rot_z", rot_z_, false);
6265
priv_nh_.param<bool>("rot_x", rot_x_, false);
6366
priv_nh_.param<bool>("rot_y", rot_y_, false);
6467

6568
frame_broadcast_timer_ = nh_.createTimer(ros::Duration(update_rate_), &FramePublisher::frameBroadcastCallback, this);
6669

67-
ros::Duration(1.0).sleep(); //give tf_listener some time
70+
ros::Duration(1.0).sleep(); // give tf_listener some time
6871

6972
return true;
7073
}
7174

72-
/// Broadcast a frame aligned with the base frame but rotated around specified axes as rotation_frame
75+
/// Broadcast a frame aligned with the base frame but rotated around specified axes as rotation_frame
7376
void FramePublisher::frameBroadcastCallback(const ros::TimerEvent& event)
7477
{
7578
ros::Time time = event.current_real;
7679
geometry_msgs::TransformStamped transform_msg;
77-
try{
78-
transform_msg = tf_buffer_.lookupTransform(base_frame_, rotation_frame_, time, ros::Duration(0.1));
80+
try
81+
{
82+
transform_msg = tf_buffer_.lookupTransform(from_frame_, to_frame_, time, ros::Duration(0.1));
7983
}
80-
catch(tf2::TransformException &ex)
84+
catch (tf2::TransformException& ex)
8185
{
82-
ROS_ERROR("FramePublisher::frameBroadcastCallback: \n%s",ex.what());
86+
ROS_ERROR("FramePublisher::frameBroadcastCallback: \n%s", ex.what());
8387
return;
8488
}
85-
//ROS_WARN_STREAM("FramePublisher::frameBroadcastCallback: \n" << transform_msg);
8689

8790
tf2::Stamped<tf2::Transform> transform_tf;
8891
tf2::fromMsg(transform_msg, transform_tf);
8992
double rot_frame_roll, rot_frame_pitch, rot_frame_yaw;
9093
transform_tf.getBasis().getRPY(rot_frame_roll, rot_frame_pitch, rot_frame_yaw);
9194

9295
// Use rotations according to settings
93-
double target_frame_roll = 0;
94-
double target_frame_pitch = 0;
95-
double target_frame_yaw = 0;
96-
if (rot_z_){ target_frame_yaw = rot_frame_yaw;}
97-
if (rot_x_){ target_frame_roll = rot_frame_roll;}
98-
if (rot_y_){ target_frame_pitch = rot_frame_pitch;}
96+
double published_frame_roll = 0;
97+
double published_frame_pitch = 0;
98+
double published_frame_yaw = 0;
99+
if (rot_x_){ published_frame_roll = rot_frame_roll; }
100+
if (rot_y_){ published_frame_pitch = rot_frame_pitch; }
101+
if (rot_z_){ published_frame_yaw = rot_frame_yaw; }
99102

100-
tf2::Stamped<tf2::Transform> target_tf(transform_tf); //keep header
101-
target_tf.setOrigin(tf2::Vector3(0,0,0));
102-
target_tf.getBasis().setRPY(target_frame_roll, target_frame_pitch, target_frame_yaw);
103+
tf2::Stamped<tf2::Transform> published_tf(transform_tf); // keep header and translation
104+
if (!use_to_frame_translation_){ published_tf.setOrigin(tf2::Vector3(0,0,0)); }
105+
published_tf.getBasis().setRPY(published_frame_roll, published_frame_pitch, published_frame_yaw);
103106

104107
// Broadcast new frame
105-
geometry_msgs::TransformStamped target_msg = tf2::toMsg(target_tf);
106-
target_msg.child_frame_id = target_frame_;
107-
//ROS_ERROR_STREAM("FramePublisher::frameBroadcastCallback: \n" << target_msg);
108-
tf_broadcaster_.sendTransform(target_msg);
108+
geometry_msgs::TransformStamped published_msg = tf2::toMsg(published_tf);
109+
published_msg.child_frame_id = frame_name_;
110+
tf_broadcaster_.sendTransform(published_msg);
109111
}

0 commit comments

Comments
 (0)