HiepLM update

This commit is contained in:
2025-12-30 09:06:48 +07:00
parent 3c51b228ec
commit 2987c1a481
8 changed files with 158 additions and 158 deletions

View File

@@ -4,7 +4,7 @@
#include <tf3/time.h>
#include <tf3/compat.h>
#include <tf3/LinearMath/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <robot_geometry_msgs/TransformStamped.h>
#include <robot/time.h>
#include <cmath>
@@ -27,15 +27,15 @@ namespace tf3
return time_tmp;
}
inline tf3::Quaternion convertQuaternion(const geometry_msgs::Quaternion& q)
inline tf3::Quaternion convertQuaternion(const robot_geometry_msgs::Quaternion& q)
{
tf3::Quaternion out(q.x,q.y,q.z,q.w);
return out;
}
inline geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
inline robot_geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
{
return geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
return robot_geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
}
inline tf3::Transform convertToTransform(const tf3::TransformStampedMsg& msg)
@@ -59,7 +59,7 @@ namespace tf3
return out;
}
inline tf3::Transform convertToTransform(const geometry_msgs::TransformStamped& msg)
inline tf3::Transform convertToTransform(const robot_geometry_msgs::TransformStamped& msg)
{
tf3::Transform out;
@@ -81,7 +81,7 @@ namespace tf3
}
inline tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
inline tf3::TransformStampedMsg convertToTransformStampedMsg(const robot_geometry_msgs::TransformStamped& msg)
{
tf3::TransformStampedMsg out;
out.header.seq = msg.header.seq;
@@ -98,9 +98,9 @@ namespace tf3
return out;
}
inline geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
inline robot_geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
{
geometry_msgs::TransformStamped out;
robot_geometry_msgs::TransformStamped out;
out.header.seq = msg.header.seq;
out.header.stamp = convertTime(msg.header.stamp);
out.header.frame_id = msg.header.frame_id;

View File

@@ -29,7 +29,7 @@
#include <tf3_sensor_msgs/tf3_sensor_msgs.h>
#include <geometry_msgs/PoseStamped.h>
#include <robot_geometry_msgs/PoseStamped.h>
#include <gtest/gtest.h>
#include <tf3/buffer_core.h>
@@ -97,7 +97,7 @@ int main(int argc, char **argv){
tf_buffer = new tf3::BufferCore();
// populate buffer
geometry_msgs::TransformStamped t;
robot_geometry_msgs::TransformStamped t;
t.transform.translation.x = 10;
t.transform.translation.y = 20;
t.transform.translation.z = 30;