update file data_convert.h
This commit is contained in:
parent
6e548f71fb
commit
d3588f0bb5
|
|
@ -11,7 +11,7 @@
|
||||||
namespace tf3
|
namespace tf3
|
||||||
{
|
{
|
||||||
|
|
||||||
robot::Time convertTime(const tf3::Time& time)
|
inline robot::Time convertTime(const tf3::Time& time)
|
||||||
{
|
{
|
||||||
robot::Time time_tmp;
|
robot::Time time_tmp;
|
||||||
time_tmp.sec = time.sec;
|
time_tmp.sec = time.sec;
|
||||||
|
|
@ -19,7 +19,7 @@ namespace tf3
|
||||||
return time_tmp;
|
return time_tmp;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Time convertTime(const robot::Time& time)
|
inline tf3::Time convertTime(const robot::Time& time)
|
||||||
{
|
{
|
||||||
tf3::Time time_tmp;
|
tf3::Time time_tmp;
|
||||||
time_tmp.sec = time.sec;
|
time_tmp.sec = time.sec;
|
||||||
|
|
@ -27,18 +27,18 @@ namespace tf3
|
||||||
return time_tmp;
|
return time_tmp;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Quaternion convertQuaternion(const geometry_msgs::Quaternion& q)
|
inline tf3::Quaternion convertQuaternion(const geometry_msgs::Quaternion& q)
|
||||||
{
|
{
|
||||||
tf3::Quaternion out(q.x,q.y,q.z,q.w);
|
tf3::Quaternion out(q.x,q.y,q.z,q.w);
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
|
inline geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
|
||||||
{
|
{
|
||||||
return geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
|
return geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Transform convertToTransform(const tf3::TransformStampedMsg& msg)
|
inline tf3::Transform convertToTransform(const tf3::TransformStampedMsg& msg)
|
||||||
{
|
{
|
||||||
tf3::Transform out;
|
tf3::Transform out;
|
||||||
|
|
||||||
|
|
@ -59,7 +59,7 @@ namespace tf3
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Transform convertToTransform(const geometry_msgs::TransformStamped& msg)
|
inline tf3::Transform convertToTransform(const geometry_msgs::TransformStamped& msg)
|
||||||
{
|
{
|
||||||
tf3::Transform out;
|
tf3::Transform out;
|
||||||
|
|
||||||
|
|
@ -81,7 +81,7 @@ namespace tf3
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
inline tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
||||||
{
|
{
|
||||||
tf3::TransformStampedMsg out;
|
tf3::TransformStampedMsg out;
|
||||||
out.header.seq = msg.header.seq;
|
out.header.seq = msg.header.seq;
|
||||||
|
|
@ -98,7 +98,7 @@ namespace tf3
|
||||||
|
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
|
inline geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
|
||||||
{
|
{
|
||||||
geometry_msgs::TransformStamped out;
|
geometry_msgs::TransformStamped out;
|
||||||
out.header.seq = msg.header.seq;
|
out.header.seq = msg.header.seq;
|
||||||
|
|
|
||||||
|
|
@ -252,6 +252,12 @@ TEST(TfGeometry, PoseWithCovarianceStamped)
|
||||||
int main(int argc, char **argv){
|
int main(int argc, char **argv){
|
||||||
testing::InitGoogleTest(&argc, argv);
|
testing::InitGoogleTest(&argc, argv);
|
||||||
|
|
||||||
|
// std::vector<int> data = {2,2,7,4,5};
|
||||||
|
// for(int i = 0; i < data.size(); i++) {
|
||||||
|
// std::cout << data.size() << std::endl;
|
||||||
|
// std::cout<< i << " " << data[i] << std::endl;
|
||||||
|
// }
|
||||||
|
|
||||||
tf_buffer = new tf3::BufferCore();
|
tf_buffer = new tf3::BufferCore();
|
||||||
tf_buffer->setUsingDedicatedThread(true);
|
tf_buffer->setUsingDedicatedThread(true);
|
||||||
// std::cout << "STEP 1" << std::endl;
|
// std::cout << "STEP 1" << std::endl;
|
||||||
|
|
|
||||||
|
|
@ -11,7 +11,7 @@
|
||||||
namespace tf3
|
namespace tf3
|
||||||
{
|
{
|
||||||
|
|
||||||
robot::Time convertTime(const tf3::Time& time)
|
inline robot::Time convertTime(const tf3::Time& time)
|
||||||
{
|
{
|
||||||
robot::Time time_tmp;
|
robot::Time time_tmp;
|
||||||
time_tmp.sec = time.sec;
|
time_tmp.sec = time.sec;
|
||||||
|
|
@ -19,7 +19,7 @@ namespace tf3
|
||||||
return time_tmp;
|
return time_tmp;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Time convertTime(const robot::Time& time)
|
inline tf3::Time convertTime(const robot::Time& time)
|
||||||
{
|
{
|
||||||
tf3::Time time_tmp;
|
tf3::Time time_tmp;
|
||||||
time_tmp.sec = time.sec;
|
time_tmp.sec = time.sec;
|
||||||
|
|
@ -27,18 +27,18 @@ namespace tf3
|
||||||
return time_tmp;
|
return time_tmp;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Quaternion convertQuaternion(const geometry_msgs::Quaternion& q)
|
inline tf3::Quaternion convertQuaternion(const geometry_msgs::Quaternion& q)
|
||||||
{
|
{
|
||||||
tf3::Quaternion out(q.x,q.y,q.z,q.w);
|
tf3::Quaternion out(q.x,q.y,q.z,q.w);
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
|
inline geometry_msgs::Quaternion convertQuaternion(const tf3::Quaternion& q)
|
||||||
{
|
{
|
||||||
return geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
|
return geometry_msgs::Quaternion(q.x(),q.y(),q.z(),q.w());
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Transform convertToTransform(const tf3::TransformStampedMsg& msg)
|
inline tf3::Transform convertToTransform(const tf3::TransformStampedMsg& msg)
|
||||||
{
|
{
|
||||||
tf3::Transform out;
|
tf3::Transform out;
|
||||||
|
|
||||||
|
|
@ -59,7 +59,7 @@ namespace tf3
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
tf3::Transform convertToTransform(const geometry_msgs::TransformStamped& msg)
|
inline tf3::Transform convertToTransform(const geometry_msgs::TransformStamped& msg)
|
||||||
{
|
{
|
||||||
tf3::Transform out;
|
tf3::Transform out;
|
||||||
|
|
||||||
|
|
@ -81,7 +81,7 @@ namespace tf3
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
inline tf3::TransformStampedMsg convertToTransformStampedMsg(const geometry_msgs::TransformStamped& msg)
|
||||||
{
|
{
|
||||||
tf3::TransformStampedMsg out;
|
tf3::TransformStampedMsg out;
|
||||||
out.header.seq = msg.header.seq;
|
out.header.seq = msg.header.seq;
|
||||||
|
|
@ -98,7 +98,7 @@ namespace tf3
|
||||||
|
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
|
inline geometry_msgs::TransformStamped convertToTransformStamped(const tf3::TransformStampedMsg& msg)
|
||||||
{
|
{
|
||||||
geometry_msgs::TransformStamped out;
|
geometry_msgs::TransformStamped out;
|
||||||
out.header.seq = msg.header.seq;
|
out.header.seq = msg.header.seq;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue
Block a user