update to tf3
This commit is contained in:
@@ -2,13 +2,13 @@
|
||||
#define DATA_CONVERT_H
|
||||
|
||||
#include <geometry_msgs/TransformStamped.h>
|
||||
#include <tf2/utils.h>
|
||||
#include <tf2/compat.h>
|
||||
#include <tf3/utils.h>
|
||||
#include <tf3/compat.h>
|
||||
#include <robot/time.h>
|
||||
|
||||
namespace laser_geometry
|
||||
{
|
||||
robot::Time convertTime(tf2::Time time)
|
||||
robot::Time convertTime(tf3::Time time)
|
||||
{
|
||||
robot::Time time_tmp;
|
||||
time_tmp.sec = time.sec;
|
||||
@@ -16,56 +16,56 @@ namespace laser_geometry
|
||||
return time_tmp;
|
||||
}
|
||||
|
||||
tf2::Time convertTime(robot::Time time)
|
||||
tf3::Time convertTime(robot::Time time)
|
||||
{
|
||||
tf2::Time time_tmp;
|
||||
tf3::Time time_tmp;
|
||||
time_tmp.sec = time.sec;
|
||||
time_tmp.nsec = time.nsec;
|
||||
return time_tmp;
|
||||
}
|
||||
|
||||
|
||||
tf2::Transform convertToTf2Transform(const geometry_msgs::Transform& msg)
|
||||
tf3::Transform convertToTf2Transform(const geometry_msgs::Transform& msg)
|
||||
{
|
||||
tf2::Quaternion q(
|
||||
tf3::Quaternion q(
|
||||
msg.rotation.x,
|
||||
msg.rotation.y,
|
||||
msg.rotation.z,
|
||||
msg.rotation.w
|
||||
);
|
||||
|
||||
tf2::Vector3 t(
|
||||
tf3::Vector3 t(
|
||||
msg.translation.x,
|
||||
msg.translation.y,
|
||||
msg.translation.z
|
||||
);
|
||||
|
||||
tf2::Transform tf(q, t);
|
||||
tf3::Transform tf(q, t);
|
||||
return tf;
|
||||
}
|
||||
|
||||
tf2::Transform convertToTf2Transform(const tf2::TransformMsg& msg)
|
||||
tf3::Transform convertToTf2Transform(const tf3::TransformMsg& msg)
|
||||
{
|
||||
tf2::Quaternion q(
|
||||
tf3::Quaternion q(
|
||||
msg.rotation.x,
|
||||
msg.rotation.y,
|
||||
msg.rotation.z,
|
||||
msg.rotation.w
|
||||
);
|
||||
|
||||
tf2::Vector3 t(
|
||||
tf3::Vector3 t(
|
||||
msg.translation.x,
|
||||
msg.translation.y,
|
||||
msg.translation.z
|
||||
);
|
||||
|
||||
tf2::Transform tf(q, t);
|
||||
tf3::Transform tf(q, t);
|
||||
return tf;
|
||||
}
|
||||
|
||||
tf2::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
||||
tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
||||
{
|
||||
tf2::TransformStampedMsg out;
|
||||
tf3::TransformStampedMsg out;
|
||||
out.header.seq = msg.header.seq;
|
||||
out.header.stamp = convertTime(msg.header.stamp);
|
||||
out.header.frame_id = msg.header.frame_id;
|
||||
@@ -79,7 +79,7 @@ namespace laser_geometry
|
||||
out.transform.rotation.w = msg.transform.rotation.w;
|
||||
return out;
|
||||
}
|
||||
geometry_msgs::TransformStamped convertToTransformStamped(const tf2::TransformStampedMsg& msg)
|
||||
geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
|
||||
{
|
||||
geometry_msgs::TransformStamped out;
|
||||
out.header.seq = msg.header.seq;
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
|
||||
#include <Eigen/Core> // NOLINT (cpplint cannot handle include order here)
|
||||
|
||||
#include "tf2/buffer_core.h"
|
||||
#include "tf3/buffer_core.h"
|
||||
#include <sensor_msgs/LaserScan.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <geometry_msgs/TransformStamped.h>
|
||||
@@ -142,7 +142,7 @@ public:
|
||||
* \param target_frame The frame of the resulting point cloud
|
||||
* \param scan_in The input laser scan
|
||||
* \param cloud_out The output point cloud
|
||||
* \param tf a tf2::BufferCore object to use to perform the
|
||||
* \param tf a tf3::BufferCore object to use to perform the
|
||||
* transform
|
||||
* \param range_cutoff An additional range cutoff which can be
|
||||
* applied to discard everything above it.
|
||||
@@ -157,7 +157,7 @@ public:
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf2::BufferCore & tf,
|
||||
tf3::BufferCore & tf,
|
||||
double range_cutoff = -1.0,
|
||||
int channel_options = channel_option::Default)
|
||||
{
|
||||
@@ -178,7 +178,7 @@ private:
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf2::BufferCore & tf,
|
||||
tf3::BufferCore & tf,
|
||||
double range_cutoff,
|
||||
int channel_options);
|
||||
|
||||
@@ -187,10 +187,10 @@ private:
|
||||
const std::string & target_frame,
|
||||
const sensor_msgs::LaserScan & scan_in,
|
||||
sensor_msgs::PointCloud2 & cloud_out,
|
||||
tf2::Quaternion quat_start,
|
||||
tf2::Vector3 origin_start,
|
||||
tf2::Quaternion quat_end,
|
||||
tf2::Vector3 origin_end,
|
||||
tf3::Quaternion quat_start,
|
||||
tf3::Vector3 origin_start,
|
||||
tf3::Quaternion quat_end,
|
||||
tf3::Vector3 origin_end,
|
||||
double range_cutoff,
|
||||
int channel_options);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user