ros_utils.hpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293
  1. // SPDX-License-Identifier: BSD-2-Clause
  2. #ifndef ROS_UTILS_HPP
  3. #define ROS_UTILS_HPP
  4. #include <Eigen/Dense>
  5. #include <ros/ros.h>
  6. #include <nav_msgs/Odometry.h>
  7. #include <geometry_msgs/Pose.h>
  8. #include <geometry_msgs/TransformStamped.h>
  9. namespace hdl_graph_slam {
  10. /**
  11. * @brief convert Eigen::Matrix to geometry_msgs::TransformStamped
  12. * @param stamp timestamp
  13. * @param pose Eigen::Matrix to be converted
  14. * @param frame_id tf frame_id
  15. * @param child_frame_id tf child frame_id
  16. * @return converted TransformStamped
  17. */
  18. static geometry_msgs::TransformStamped matrix2transform(const ros::Time& stamp, const Eigen::Matrix4f& pose, const std::string& frame_id, const std::string& child_frame_id) {
  19. Eigen::Quaternionf quat(pose.block<3, 3>(0, 0));
  20. quat.normalize();
  21. geometry_msgs::Quaternion odom_quat;
  22. odom_quat.w = quat.w();
  23. odom_quat.x = quat.x();
  24. odom_quat.y = quat.y();
  25. odom_quat.z = quat.z();
  26. geometry_msgs::TransformStamped odom_trans;
  27. odom_trans.header.stamp = stamp;
  28. odom_trans.header.frame_id = frame_id;
  29. odom_trans.child_frame_id = child_frame_id;
  30. odom_trans.transform.translation.x = pose(0, 3);
  31. odom_trans.transform.translation.y = pose(1, 3);
  32. odom_trans.transform.translation.z = pose(2, 3);
  33. odom_trans.transform.rotation = odom_quat;
  34. return odom_trans;
  35. }
  36. static Eigen::Isometry3d pose2isometry(const geometry_msgs::Pose& pose) {
  37. Eigen::Isometry3d mat = Eigen::Isometry3d::Identity();
  38. mat.translation() = Eigen::Vector3d(pose.position.x, pose.position.y, pose.position.z);
  39. mat.linear() = Eigen::Quaterniond(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z).toRotationMatrix();
  40. return mat;
  41. }
  42. static Eigen::Isometry3d tf2isometry(const tf::StampedTransform& trans) {
  43. Eigen::Isometry3d mat = Eigen::Isometry3d::Identity();
  44. mat.translation() = Eigen::Vector3d(trans.getOrigin().x(), trans.getOrigin().y(), trans.getOrigin().z());
  45. mat.linear() = Eigen::Quaterniond(trans.getRotation().w(), trans.getRotation().x(), trans.getRotation().y(), trans.getRotation().z()).toRotationMatrix();
  46. return mat;
  47. }
  48. static geometry_msgs::Pose isometry2pose(const Eigen::Isometry3d& mat) {
  49. Eigen::Quaterniond quat(mat.linear());
  50. Eigen::Vector3d trans = mat.translation();
  51. geometry_msgs::Pose pose;
  52. pose.position.x = trans.x();
  53. pose.position.y = trans.y();
  54. pose.position.z = trans.z();
  55. pose.orientation.w = quat.w();
  56. pose.orientation.x = quat.x();
  57. pose.orientation.y = quat.y();
  58. pose.orientation.z = quat.z();
  59. return pose;
  60. }
  61. static Eigen::Isometry3d odom2isometry(const nav_msgs::OdometryConstPtr& odom_msg) {
  62. const auto& orientation = odom_msg->pose.pose.orientation;
  63. const auto& position = odom_msg->pose.pose.position;
  64. Eigen::Quaterniond quat;
  65. quat.w() = orientation.w;
  66. quat.x() = orientation.x;
  67. quat.y() = orientation.y;
  68. quat.z() = orientation.z;
  69. Eigen::Isometry3d isometry = Eigen::Isometry3d::Identity();
  70. isometry.linear() = quat.toRotationMatrix();
  71. isometry.translation() = Eigen::Vector3d(position.x, position.y, position.z);
  72. return isometry;
  73. }
  74. } // namespace hdl_graph_slam
  75. #endif // ROS_UTILS_HPP