Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

frame_fix : now transforms the tf and odom message to base_link #231

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 34 additions & 9 deletions ros/ros1/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ using utils::GetTimestamps;
using utils::PointCloud2ToEigen;

OdometryServer::OdometryServer(const ros::NodeHandle &nh, const ros::NodeHandle &pnh)
: nh_(nh), pnh_(pnh) {
: nh_(nh), pnh_(pnh) , tf_buffer_(new tf2_ros::Buffer()), tf2_listener_(new tf2_ros::TransformListener(*tf_buffer_)){
pnh_.param("child_frame", child_frame_, child_frame_);
pnh_.param("odom_frame", odom_frame_, odom_frame_);
pnh_.param("publish_alias_tf", publish_alias_tf_, true);
Expand Down Expand Up @@ -103,6 +103,16 @@ OdometryServer::OdometryServer(const ros::NodeHandle &nh, const ros::NodeHandle
br.sendTransform(alias_transform_msg);
}

try
{
tf_buffer_->canTransform("os_sensor", "base_link", ros::Time::now(), ros::Duration(5.0));
os_to_base_link_tf_ = tf_buffer_->lookupTransform("os_sensor", "base_link", ros::Time(0));
}
catch (tf2::TransformException& ex)
{
ROS_ERROR("Failed to wait for transform: %s", ex.what());
}

// publish odometry msg
ROS_INFO("KISS-ICP ROS 1 Odometry Node Initialized");
}
Expand All @@ -125,6 +135,7 @@ void OdometryServer::RegisterFrame(const sensor_msgs::PointCloud2::ConstPtr &msg
const Eigen::Quaterniond q_current = pose.unit_quaternion();

// Broadcast the tf
geometry_msgs::TransformStamped result_transform ;
if (publish_odom_tf_) {
geometry_msgs::TransformStamped transform_msg;
transform_msg.header.stamp = msg->header.stamp;
Expand All @@ -137,18 +148,32 @@ void OdometryServer::RegisterFrame(const sensor_msgs::PointCloud2::ConstPtr &msg
transform_msg.transform.translation.x = t_current.x();
transform_msg.transform.translation.y = t_current.y();
transform_msg.transform.translation.z = t_current.z();
tf_broadcaster_.sendTransform(transform_msg);

tf2::Transform odom_to_sensor_tf;
tf2::fromMsg(transform_msg.transform, odom_to_sensor_tf);

tf2::Transform os_to_base_link_tf;
tf2::fromMsg(os_to_base_link_tf_.transform, os_to_base_link_tf);

tf2::Transform result_transform_tf = odom_to_sensor_tf * os_to_base_link_tf;
result_transform.transform = tf2::toMsg(result_transform_tf);

result_transform.header.stamp = msg->header.stamp;
result_transform.header.frame_id = odom_frame_;
result_transform.child_frame_id = child_frame_;
result_transform.transform.translation.z = t_current.z();
tf_broadcaster_.sendTransform(result_transform);
}

// publish trajectory msg
geometry_msgs::PoseStamped pose_msg;
pose_msg.pose.orientation.x = q_current.x();
pose_msg.pose.orientation.y = q_current.y();
pose_msg.pose.orientation.z = q_current.z();
pose_msg.pose.orientation.w = q_current.w();
pose_msg.pose.position.x = t_current.x();
pose_msg.pose.position.y = t_current.y();
pose_msg.pose.position.z = t_current.z();
pose_msg.pose.orientation.x = result_transform.transform.rotation.x;
pose_msg.pose.orientation.y = result_transform.transform.rotation.y;
pose_msg.pose.orientation.z = result_transform.transform.rotation.z;
pose_msg.pose.orientation.w = result_transform.transform.rotation.w;
pose_msg.pose.position.x = result_transform.transform.translation.x;
pose_msg.pose.position.y = result_transform.transform.translation.y;
pose_msg.pose.position.z = result_transform.transform.translation.z;
pose_msg.header.stamp = msg->header.stamp;
pose_msg.header.frame_id = odom_frame_;
path_msg_.poses.push_back(pose_msg);
Expand Down
9 changes: 9 additions & 0 deletions ros/ros1/OdometryServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,10 @@
#include <sensor_msgs/PointCloud2.h>
#include <tf2_ros/transform_broadcaster.h>

#include <tf2/transform_datatypes.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

namespace kiss_icp_ros {

class OdometryServer {
Expand Down Expand Up @@ -70,6 +74,11 @@ class OdometryServer {
/// Global/map coordinate frame.
std::string odom_frame_{"odom"};
std::string child_frame_{"base_link"};

//necessary for changing frames
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf2_listener_;
geometry_msgs::TransformStamped os_to_base_link_tf_;
};

} // namespace kiss_icp_ros