|
23 | 23 | #include <pcl_msgs/PolygonMesh.h> |
24 | 24 | #include <pcl_ros/point_cloud.h> |
25 | 25 |
|
| 26 | +#include <tf2_ros/static_transform_broadcaster.h> |
| 27 | + |
26 | 28 | namespace VIO { |
27 | 29 |
|
28 | 30 | RosBaseDataProvider::RosBaseDataProvider() |
@@ -59,18 +61,34 @@ RosBaseDataProvider::RosBaseDataProvider() |
59 | 61 | CHECK(!base_link_frame_id_.empty()); |
60 | 62 | CHECK(nh_private_.getParam("world_frame_id", world_frame_id_)); |
61 | 63 | CHECK(!world_frame_id_.empty()); |
| 64 | + CHECK(nh_private_.getParam("left_cam_frame_id", left_cam_frame_id_)); |
| 65 | + CHECK(!left_cam_frame_id_.empty()); |
| 66 | + CHECK(nh_private_.getParam("right_cam_frame_id", right_cam_frame_id_)); |
| 67 | + CHECK(!right_cam_frame_id_.empty()); |
62 | 68 |
|
63 | 69 | // Publishers |
64 | | - odometry_pub_ = nh_.advertise<nav_msgs::Odometry>("odometry", 10); |
| 70 | + odometry_pub_ = nh_.advertise<nav_msgs::Odometry>("odometry", 10, true); |
65 | 71 | frontend_stats_pub_ = |
66 | 72 | nh_.advertise<std_msgs::Float64MultiArray>("frontend_stats", 10); |
67 | 73 | resiliency_pub_ = |
68 | 74 | nh_.advertise<std_msgs::Float64MultiArray>("resiliency", 10); |
69 | 75 | imu_bias_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("imu_bias", 10); |
70 | 76 | pointcloud_pub_ = |
71 | | - nh_.advertise<PointCloudXYZRGB>("time_horizon_pointcloud", 10); |
72 | | - mesh_3d_frame_pub_ = nh_.advertise<pcl_msgs::PolygonMesh>("mesh", 5); |
73 | | - debug_img_pub_ = it_->advertise("debug_mesh_img", 10); |
| 77 | + nh_.advertise<PointCloudXYZRGB>("time_horizon_pointcloud", 10, true); |
| 78 | + mesh_3d_frame_pub_ = nh_.advertise<pcl_msgs::PolygonMesh>("mesh", 5, true); |
| 79 | + debug_img_pub_ = it_->advertise("debug_mesh_img", 10, true); |
| 80 | + |
| 81 | + // Static TFs for left/right cameras |
| 82 | + const gtsam::Pose3& body_Pose_left_cam = |
| 83 | + stereo_calib_.left_camera_info_.body_Pose_cam_; |
| 84 | + const gtsam::Pose3& body_Pose_right_cam = |
| 85 | + stereo_calib_.right_camera_info_.body_Pose_cam_; |
| 86 | + publishStaticTf(body_Pose_left_cam, |
| 87 | + base_link_frame_id_, |
| 88 | + left_cam_frame_id_); |
| 89 | + publishStaticTf(body_Pose_right_cam, |
| 90 | + base_link_frame_id_, |
| 91 | + right_cam_frame_id_); |
74 | 92 | } |
75 | 93 |
|
76 | 94 | RosBaseDataProvider::~RosBaseDataProvider() {} |
@@ -743,6 +761,26 @@ void RosBaseDataProvider::publishImuBias( |
743 | 761 | imu_bias_pub_.publish(imu_bias_msg); |
744 | 762 | } |
745 | 763 |
|
| 764 | +void RosBaseDataProvider::publishStaticTf(const gtsam::Pose3& pose, |
| 765 | + const std::string& parent_frame_id, |
| 766 | + const std::string& child_frame_id) { |
| 767 | + static tf2_ros::StaticTransformBroadcaster static_broadcaster; |
| 768 | + geometry_msgs::TransformStamped static_transform_stamped; |
| 769 | + // TODO(Toni): Warning: using ros::Time::now(), will that bring issues? |
| 770 | + static_transform_stamped.header.stamp = ros::Time::now(); |
| 771 | + static_transform_stamped.header.frame_id = parent_frame_id; |
| 772 | + static_transform_stamped.child_frame_id = child_frame_id; |
| 773 | + static_transform_stamped.transform.translation.x = pose.x(); |
| 774 | + static_transform_stamped.transform.translation.y = pose.y(); |
| 775 | + static_transform_stamped.transform.translation.z = pose.z(); |
| 776 | + const gtsam::Quaternion& quat = pose.rotation().toQuaternion(); |
| 777 | + static_transform_stamped.transform.rotation.x = quat.x(); |
| 778 | + static_transform_stamped.transform.rotation.y = quat.y(); |
| 779 | + static_transform_stamped.transform.rotation.z = quat.z(); |
| 780 | + static_transform_stamped.transform.rotation.w = quat.w(); |
| 781 | + static_broadcaster.sendTransform(static_transform_stamped); |
| 782 | +} |
| 783 | + |
746 | 784 | void RosBaseDataProvider::printParsedParams() const { |
747 | 785 | LOG(INFO) << std::string(80, '=') << '\n' |
748 | 786 | << ">>>>>>>>> RosDataProvider::print <<<<<<<<<<<" << '\n' |
|
0 commit comments