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

Upgrade to tf2 #1

Merged
merged 2 commits into from
Jan 8, 2025
Merged
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
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ This is the main Robot-Centric Elevation Mapping node. It uses the distance sens

The robot pose and covariance.

* **`/tf`** ([tf/tfMessage])
* **`/tf`** ([tf2_msgs/TFMessage])

The transformation tree.

Expand Down Expand Up @@ -432,7 +432,7 @@ Please report bugs and request features using the [Issue Tracker](https://github
[grid_map_msgs/GridMap]: https://github.com/anybotics/grid_map/blob/master/grid_map_msgs/msg/GridMap.msg
[sensor_msgs/PointCloud2]: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
[geometry_msgs/PoseWithCovarianceStamped]: http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html
[tf/tfMessage]: http://docs.ros.org/kinetic/api/tf/html/msg/tfMessage.html
[tf2_msgs/TFMessage]: http://docs.ros.org/en/noetic/api/tf2_msgs/html/msg/TFMessage.html
[std_srvs/Empty]: http://docs.ros.org/api/std_srvs/html/srv/Empty.html
[grid_map_msgs/GetGridMap]: https://github.com/anybotics/grid_map/blob/master/grid_map_msgs/srv/GetGridMap.srv
[grid_map_msgs/ProcessFile]: https://github.com/ANYbotics/grid_map/blob/master/grid_map_msgs/srv/ProcessFile.srv
12 changes: 7 additions & 5 deletions elevation_mapping/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ add_compile_options(-Wall -Wextra -Wpedantic)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

set(
CATKIN_PACKAGE_DEPENDENCIES
CATKIN_PACKAGE_DEPENDENCIES
eigen_conversions
grid_map_core
grid_map_ros
Expand All @@ -20,11 +20,13 @@ set(
roscpp
sensor_msgs
std_msgs
tf
tf_conversions
tf2
tf2_ros
tf2_eigen
tf2_geometry_msgs
)

find_package(catkin REQUIRED
find_package(catkin REQUIRED
COMPONENTS
${CATKIN_PACKAGE_DEPENDENCIES}
)
Expand Down Expand Up @@ -111,7 +113,7 @@ target_link_libraries(${PROJECT_NAME}
#############

install(
TARGETS
TARGETS
${PROJECT_NAME}
${PROJECT_NAME}_pcl_types
${PROJECT_NAME}_library
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@
#include <sensor_msgs/PointCloud2.h>
#include <std_srvs/Empty.h>
#include <std_srvs/Trigger.h>
#include <tf/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

// Eigen
#include <Eigen/Core>
Expand Down Expand Up @@ -298,8 +299,9 @@ class ElevationMapping {
//! Cache for the robot pose messages.
message_filters::Cache<geometry_msgs::PoseWithCovarianceStamped> robotPoseCache_;

//! TF listener and broadcaster.
tf::TransformListener transformListener_;
//! TF listener and buffer.
tf2_ros::Buffer transformBuffer_;
tf2_ros::TransformListener transformListener_;

struct Parameters {
//! Size of the cache for the robot pose messages.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@

// ROS
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

// Eigen
#include <Eigen/Core>
Expand Down Expand Up @@ -139,8 +140,9 @@ class SensorProcessorBase {
//! ROS nodehandle.
ros::NodeHandle& nodeHandle_;

//! TF transform listener.
tf::TransformListener transformListener_;
//! TF transform listener and buffer.
tf2_ros::Buffer transformBuffer_;
tf2_ros::TransformListener transformListener_;

//! Rotation from Base to Sensor frame (C_SB)
kindr::RotationMatrixD rotationBaseToSensor_;
Expand Down
6 changes: 4 additions & 2 deletions elevation_mapping/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,10 @@
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>tf</depend>
<depend>tf_conversions</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>

<!-- <test_depend>cmake_code_coverage</test_depend> -->
<test_depend>grid_map_filters</test_depend>
Expand Down
19 changes: 13 additions & 6 deletions elevation_mapping/src/ElevationMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,10 @@
#include <grid_map_ros/grid_map_ros.hpp>
#include <kindr/Core>
#include <kindr_ros/kindr_ros.hpp>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/PointStamped.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include "elevation_mapping/ElevationMap.hpp"
#include "elevation_mapping/ElevationMapping.hpp"
Expand All @@ -35,6 +39,7 @@ namespace elevation_mapping {
ElevationMapping::ElevationMapping(ros::NodeHandle& nodeHandle)
: nodeHandle_(nodeHandle),
inputSources_(nodeHandle_),
transformListener_(transformBuffer_),
map_(nodeHandle),
robotMotionMapUpdater_(nodeHandle),
receivedFirstMatchingPointcloudAndPose_(false) {
Expand Down Expand Up @@ -542,8 +547,8 @@ bool ElevationMapping::updateMapLocation() {
geometry_msgs::PointStamped trackPointTransformed;

try {
transformListener_.transformPoint(map_.getFrameId(), trackPoint, trackPointTransformed);
} catch (tf::TransformException& ex) {
trackPointTransformed = transformBuffer_.transform(trackPoint, map_.getFrameId());
} catch (tf2::TransformException& ex) {
ROS_ERROR("%s", ex.what());
return false;
}
Expand Down Expand Up @@ -627,12 +632,14 @@ bool ElevationMapping::initializeElevationMap() {
if (parameters.initializeElevationMap_) {
if (static_cast<elevation_mapping::InitializationMethods>(parameters.initializationMethod_) ==
elevation_mapping::InitializationMethods::PlanarFloorInitializer) {
tf::StampedTransform transform;
geometry_msgs::TransformStamped transform_msg;
tf2::Stamped<tf2::Transform> transform;

// Listen to transform between mapFrameId_ and targetFrameInitSubmap_ and use z value for initialization
try {
transformListener_.waitForTransform(parameters.mapFrameId_, parameters.targetFrameInitSubmap_, ros::Time(0), ros::Duration(5.0));
transformListener_.lookupTransform(parameters.mapFrameId_, parameters.targetFrameInitSubmap_, ros::Time(0), transform);
transform_msg = transformBuffer_.lookupTransform(parameters.mapFrameId_, parameters.targetFrameInitSubmap_, ros::Time(0), ros::Duration(5.0));
tf2::fromMsg(transform_msg, transform);

ROS_DEBUG_STREAM("Initializing with x: " << transform.getOrigin().x() << " y: " << transform.getOrigin().y()
<< " z: " << transform.getOrigin().z());

Expand All @@ -645,7 +652,7 @@ bool ElevationMapping::initializeElevationMap() {
map_.setRawSubmapHeight(positionRobot, transform.getOrigin().z() + parameters.initSubmapHeightOffset_,
parameters.initSubmapVariance_, parameters.lengthInXInitSubmap_, parameters.lengthInYInitSubmap_);
return true;
} catch (tf::TransformException& ex) {
} catch (tf2::TransformException& ex) {
ROS_DEBUG("%s", ex.what());
ROS_WARN("Could not initialize elevation map with constant height. (This warning can be ignored if TF tree is not available.)");
return false;
Expand Down
67 changes: 36 additions & 31 deletions elevation_mapping/src/sensor_processors/SensorProcessorBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,9 @@

#include "elevation_mapping/sensor_processors/SensorProcessorBase.hpp"

// ROS
#include <geometry_msgs/TransformStamped.h>

// PCL
#include <pcl/common/io.h>
#include <pcl/common/transforms.h>
Expand All @@ -17,7 +20,7 @@
#include <pcl/pcl_base.h>

// TF
#include <tf_conversions/tf_eigen.h>
#include <tf2_eigen/tf2_eigen.h>

// STL
#include <cmath>
Expand All @@ -29,7 +32,9 @@
namespace elevation_mapping {

SensorProcessorBase::SensorProcessorBase(ros::NodeHandle& nodeHandle, const GeneralParameters& generalConfig)
: nodeHandle_(nodeHandle), firstTfAvailable_(false) {
: nodeHandle_(nodeHandle),
transformListener_(transformBuffer_),
firstTfAvailable_(false) {
pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
transformationSensorToMap_.setIdentity();
generalParameters_ = generalConfig;
Expand Down Expand Up @@ -92,31 +97,33 @@ bool SensorProcessorBase::process(const PointCloudType::ConstPtr pointCloudInput
bool SensorProcessorBase::updateTransformations(const ros::Time& timeStamp) {
const Parameters parameters{parameters_.getData()};
try {
transformListener_.waitForTransform(sensorFrameId_, generalParameters_.mapFrameId_, timeStamp, ros::Duration(1.0));

tf::StampedTransform transformTf;
transformListener_.lookupTransform(generalParameters_.mapFrameId_, sensorFrameId_, timeStamp, transformTf);
poseTFToEigen(transformTf, transformationSensorToMap_);

transformListener_.lookupTransform(generalParameters_.robotBaseFrameId_, sensorFrameId_, timeStamp,
transformTf); // TODO(max): Why wrong direction?
Eigen::Affine3d transform;
poseTFToEigen(transformTf, transform);
rotationBaseToSensor_.setMatrix(transform.rotation().matrix());
translationBaseToSensorInBaseFrame_.toImplementation() = transform.translation();

transformListener_.lookupTransform(generalParameters_.mapFrameId_, generalParameters_.robotBaseFrameId_, timeStamp,
transformTf); // TODO(max): Why wrong direction?
poseTFToEigen(transformTf, transform);
rotationMapToBase_.setMatrix(transform.rotation().matrix());
translationMapToBaseInMapFrame_.toImplementation() = transform.translation();
geometry_msgs::TransformStamped transformGeom;
transformGeom = transformBuffer_.lookupTransform(generalParameters_.mapFrameId_, sensorFrameId_, timeStamp, ros::Duration(1.0));
transformationSensorToMap_ = tf2::transformToEigen(transformGeom);

transformGeom = transformBuffer_.lookupTransform(generalParameters_.robotBaseFrameId_, sensorFrameId_, timeStamp,
ros::Duration(1.0)); // TODO(max): Why wrong direction?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ecthelion99 - What is this TODO? Did you put it here or was it in existing code?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These were all existing

Eigen::Quaterniond rotationQuaternion;
tf2::fromMsg(transformGeom.transform.rotation, rotationQuaternion);
rotationBaseToSensor_.setMatrix(rotationQuaternion.toRotationMatrix());
Eigen::Vector3d translationVector;
tf2::fromMsg(transformGeom.transform.translation, translationVector);
translationBaseToSensorInBaseFrame_.toImplementation() = translationVector;

transformGeom = transformBuffer_.lookupTransform(generalParameters_.mapFrameId_, generalParameters_.robotBaseFrameId_,
timeStamp, ros::Duration(1.0)); // TODO(max): Why wrong direction?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ecthelion99 - same question.

tf2::fromMsg(transformGeom.transform.rotation, rotationQuaternion);
rotationMapToBase_.setMatrix(rotationQuaternion.toRotationMatrix());
tf2::fromMsg(transformGeom.transform.translation, translationVector);
translationMapToBaseInMapFrame_.toImplementation() = translationVector;

if (!firstTfAvailable_) {
firstTfAvailable_ = true;
}

return true;
} catch (tf::TransformException& ex) {
} catch (tf2::TransformException& ex) {
if (!firstTfAvailable_) {
return false;
}
Expand All @@ -131,22 +138,20 @@ bool SensorProcessorBase::transformPointCloud(PointCloudType::ConstPtr pointClou
timeStamp.fromNSec(1000 * pointCloud->header.stamp);
const std::string inputFrameId(pointCloud->header.frame_id);

tf::StampedTransform transformTf;
try {
transformListener_.waitForTransform(targetFrame, inputFrameId, timeStamp, ros::Duration(1.0), ros::Duration(0.001));
transformListener_.lookupTransform(targetFrame, inputFrameId, timeStamp, transformTf);
} catch (tf::TransformException& ex) {
geometry_msgs::TransformStamped transformGeom;
transformGeom = transformBuffer_.lookupTransform(targetFrame, inputFrameId, timeStamp, ros::Duration(1.0)); // FIXME: missing 0.001 retry duration

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What about this one?

Eigen::Affine3d transform = tf2::transformToEigen(transformGeom);
pcl::transformPointCloud(*pointCloud, *pointCloudTransformed, transform.cast<float>());
pointCloudTransformed->header.frame_id = targetFrame;

ROS_DEBUG_THROTTLE(5, "Point cloud transformed to frame %s for time stamp %f.", targetFrame.c_str(),
pointCloudTransformed->header.stamp / 1000.0);
} catch (tf2::TransformException& ex) {
ROS_ERROR("%s", ex.what());
return false;
}

Eigen::Affine3d transform;
poseTFToEigen(transformTf, transform);
pcl::transformPointCloud(*pointCloud, *pointCloudTransformed, transform.cast<float>());
pointCloudTransformed->header.frame_id = targetFrame;

ROS_DEBUG_THROTTLE(5, "Point cloud transformed to frame %s for time stamp %f.", targetFrame.c_str(),
pointCloudTransformed->header.stamp / 1000.0);
return true;
}

Expand Down
2 changes: 1 addition & 1 deletion elevation_mapping_demos/launch/simple_demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
</node> -->

<!-- Setup a transform between the world and the robot -->
<node pkg="tf" type="static_transform_publisher" name="world_to_robot" args="2.0 6.0 0 0 0.0 0 /map /base 100"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="world_to_robot" args="2.0 6.0 0.0 0.0 0.0 0.0 /map /base"/>

<!-- Launch visualizations for the resulting elevation map -->
<include file="$(find elevation_mapping_demos)/launch/visualization.launch" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<arg name="gui" value="false"/> <!-- Launch the user interface window of Gazebo-->
<arg name="headless" value="false"/> <!-- Enable gazebo state log recording-->
<arg name="debug" value="false"/> <!-- Start gzserver (Gazebo Server) in debug mode using gdb-->
<arg name="verbose" value="false"/> <!-- Start gazebo in verbose mode-->
</include>

<!-- Load robot_description param for tf, rviz and gazebo spawn. -->
Expand Down
2 changes: 1 addition & 1 deletion elevation_mapping_demos/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<exec_depend>grid_map_visualization</exec_depend>
<exec_depend>pcl_ros</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>turtlebot3_gazebo</exec_depend>
<exec_depend>xacro</exec_depend>

Expand Down
27 changes: 10 additions & 17 deletions elevation_mapping_demos/scripts/tf_to_pose_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,33 +2,25 @@

import rospy
import geometry_msgs.msg
import tf
import tf2_ros

def callback(newPose):
"""Listens to a transform between from_frame and to_frame and publishes it
as a pose with a zero covariance."""
global publisher, tf_listener, from_frame, to_frame
global publisher, tf_buffer, tf_listener, from_frame, to_frame

# Listen to transform and throw exception if the transform is not
# available.
try:
(trans, rot) = tf_listener.lookupTransform(
from_frame, to_frame, rospy.Time(0))
except (tf.LookupException, tf.ConnectivityException,
tf.ExtrapolationException):
trans = tf_buffer.lookup_transform(from_frame, to_frame, rospy.Time())
except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
return

# Create and fill pose message for publishing
pose = geometry_msgs.msg.PoseWithCovarianceStamped()
pose.header.stamp = rospy.Time(0)
pose.header.frame_id = from_frame
pose.pose.pose.position.x = trans[0]
pose.pose.pose.position.y = trans[1]
pose.pose.pose.position.z = trans[2]
pose.pose.pose.orientation.x = rot[0]
pose.pose.pose.orientation.y = rot[1]
pose.pose.pose.orientation.z = rot[2]
pose.pose.pose.orientation.w = rot[3]
pose.header = trans.header
pose.pose.pose.position = trans.transform.translation
pose.pose.pose.orientation = trans.transform.rotation

# Since tf transforms do not have a covariance, pose is filled with
# a zero covariance.
Expand All @@ -45,14 +37,15 @@ def callback(newPose):
def main_program():
""" Main function initializes node and subscribers and starts
the ROS loop. """
global publisher, tf_listener, from_frame, to_frame
global publisher, tf_buffer, tf_listener, from_frame, to_frame
rospy.init_node('tf_to_pose_publisher')
# Read frame id's for tf listener
from_frame = rospy.get_param("~from_frame")
to_frame = rospy.get_param("~to_frame")
pose_name = str(to_frame) + "_pose"

tf_listener = tf.TransformListener()
tf_buffer = tf2_ros.Buffer()
tf_listener = tf2_ros.TransformListener(tf_buffer)
publisher = rospy.Publisher(
pose_name, geometry_msgs.msg.PoseWithCovarianceStamped, queue_size=10)

Expand Down