Skip to content

Commit dff91ba

Browse files
refactor(ar_tag_based_localizer): refactor pub/sub and so on (autowarefoundation#5854)
* Fixed ar_tag_based_localizer pub/sub Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> * Remove dependency on image_transport Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp> --------- Signed-off-by: Shintaro SAKODA <shintaro.sakoda@tier4.jp>
1 parent 7477e9a commit dff91ba

File tree

7 files changed

+50
-77
lines changed

7 files changed

+50
-77
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,13 @@
11
<?xml version="1.0"?>
22
<launch>
33
<group>
4-
<push-ros-namespace namespace="ar_tag_based_localizer"/>
5-
<group>
6-
<include file="$(find-pkg-share ar_tag_based_localizer)/launch/ar_tag_based_localizer.launch.xml">
7-
<arg name="input_lanelet2_map" value="/map/vector_map"/>
8-
<arg name="input_image" value="/sensing/camera/traffic_light/image_raw"/>
9-
<arg name="input_camera_info" value="/sensing/camera/traffic_light/camera_info"/>
10-
<arg name="input_ekf_pose" value="/localization/pose_twist_fusion_filter/biased_pose_with_covariance"/>
11-
<arg name="output_image" value="/localization/pose_estimator/ar_tag_detected_image"/>
12-
<arg name="output_pose_with_covariance" value="/localization/pose_estimator/pose_with_covariance"/>
13-
<arg name="param_file" value="$(find-pkg-share ar_tag_based_localizer)/config/ar_tag_based_localizer.param.yaml"/>
14-
</include>
15-
</group>
4+
<include file="$(find-pkg-share ar_tag_based_localizer)/launch/ar_tag_based_localizer.launch.xml">
5+
<arg name="input_lanelet2_map" value="/map/vector_map"/>
6+
<arg name="input_image" value="/sensing/camera/traffic_light/image_raw"/>
7+
<arg name="input_camera_info" value="/sensing/camera/traffic_light/camera_info"/>
8+
<arg name="input_ekf_pose" value="/localization/pose_twist_fusion_filter/biased_pose_with_covariance"/>
9+
<arg name="output_pose_with_covariance" value="/localization/pose_estimator/pose_with_covariance"/>
10+
<arg name="param_file" value="$(find-pkg-share ar_tag_based_localizer)/config/ar_tag_based_localizer.param.yaml"/>
11+
</include>
1612
</group>
1713
</launch>

localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml

+8-2
Original file line numberDiff line numberDiff line change
@@ -8,18 +8,24 @@
88
<arg name="input_camera_info" default="~/input/camera_info"/>
99
<arg name="input_ekf_pose" default="~/input/ekf_pose"/>
1010

11-
<arg name="output_image" default="~/debug/result"/>
1211
<arg name="output_pose_with_covariance" default="~/output/pose_with_covariance"/>
1312

13+
<arg name="debug_image" default="~/debug/image"/>
14+
<arg name="debug_mapped_tag" default="~/debug/mapped_tag"/>
15+
<arg name="debug_detected_tag" default="~/debug/detected_tag"/>
16+
1417
<node pkg="ar_tag_based_localizer" exec="ar_tag_based_localizer" name="$(var node_name)" output="log">
1518
<remap from="~/input/lanelet2_map" to="$(var input_lanelet2_map)"/>
1619
<remap from="~/input/image" to="$(var input_image)"/>
1720
<remap from="~/input/camera_info" to="$(var input_camera_info)"/>
1821
<remap from="~/input/ekf_pose" to="$(var input_ekf_pose)"/>
1922

20-
<remap from="~/debug/result" to="$(var output_image)"/>
2123
<remap from="~/output/pose_with_covariance" to="$(var output_pose_with_covariance)"/>
2224

25+
<remap from="~/debug/image" to="$(var debug_image)"/>
26+
<remap from="~/debug/mapped_tag" to="$(var debug_mapped_tag)"/>
27+
<remap from="~/debug/detected_tag" to="$(var debug_detected_tag)"/>
28+
2329
<param from="$(var param_file)"/>
2430
</node>
2531
</launch>

localization/landmark_based_localizer/ar_tag_based_localizer/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
<depend>aruco</depend>
1818
<depend>cv_bridge</depend>
1919
<depend>diagnostic_msgs</depend>
20-
<depend>image_transport</depend>
2120
<depend>landmark_manager</depend>
2221
<depend>lanelet2_extension</depend>
2322
<depend>localization_util</depend>

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp

+27-52
Original file line numberDiff line numberDiff line change
@@ -66,10 +66,6 @@
6666

6767
ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options)
6868
: Node("ar_tag_based_localizer", options), cam_info_received_(false)
69-
{
70-
}
71-
72-
bool ArTagBasedLocalizer::setup()
7369
{
7470
/*
7571
Declare node parameters
@@ -92,7 +88,7 @@ bool ArTagBasedLocalizer::setup()
9288
} else {
9389
// Error
9490
RCLCPP_ERROR_STREAM(this->get_logger(), "Invalid detection_mode: " << detection_mode);
95-
return false;
91+
return;
9692
}
9793
ekf_pose_buffer_ = std::make_unique<SmartPoseBuffer>(
9894
this->get_logger(), ekf_time_tolerance_, ekf_position_tolerance_);
@@ -111,59 +107,50 @@ bool ArTagBasedLocalizer::setup()
111107
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
112108
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
113109

114-
/*
115-
Initialize image transport
116-
*/
117-
it_ = std::make_unique<image_transport::ImageTransport>(shared_from_this());
118-
119110
/*
120111
Subscribers
121112
*/
113+
using std::placeholders::_1;
122114
map_bin_sub_ = this->create_subscription<HADMapBin>(
123115
"~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal),
124-
std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1));
116+
std::bind(&ArTagBasedLocalizer::map_bin_callback, this, _1));
125117

126118
rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
127119
qos_sub.best_effort();
128-
pose_array_pub_ = this->create_publisher<PoseArray>("~/debug/detected_landmarks", qos_sub);
129120
image_sub_ = this->create_subscription<Image>(
130-
"~/input/image", qos_sub,
131-
std::bind(&ArTagBasedLocalizer::image_callback, this, std::placeholders::_1));
121+
"~/input/image", qos_sub, std::bind(&ArTagBasedLocalizer::image_callback, this, _1));
132122
cam_info_sub_ = this->create_subscription<CameraInfo>(
133-
"~/input/camera_info", qos_sub,
134-
std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1));
123+
"~/input/camera_info", qos_sub, std::bind(&ArTagBasedLocalizer::cam_info_callback, this, _1));
135124
ekf_pose_sub_ = this->create_subscription<PoseWithCovarianceStamped>(
136-
"~/input/ekf_pose", qos_sub,
137-
std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, std::placeholders::_1));
125+
"~/input/ekf_pose", qos_sub, std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, _1));
138126

139127
/*
140128
Publishers
141129
*/
142-
rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10));
143-
qos_marker.transient_local();
144-
qos_marker.reliable();
145-
marker_pub_ = this->create_publisher<MarkerArray>("~/debug/marker", qos_marker);
146-
rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
147-
image_pub_ = it_->advertise("~/debug/result", 1);
148-
pose_pub_ =
149-
this->create_publisher<PoseWithCovarianceStamped>("~/output/pose_with_covariance", qos_pub);
150-
diag_pub_ = this->create_publisher<DiagnosticArray>("/diagnostics", qos_pub);
130+
const rclcpp::QoS qos_pub_once = rclcpp::QoS(rclcpp::KeepLast(10)).transient_local().reliable();
131+
const rclcpp::QoS qos_pub_periodic(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
132+
pose_pub_ = this->create_publisher<PoseWithCovarianceStamped>(
133+
"~/output/pose_with_covariance", qos_pub_periodic);
134+
image_pub_ = this->create_publisher<Image>("~/debug/image", qos_pub_periodic);
135+
mapped_tag_pose_pub_ = this->create_publisher<MarkerArray>("~/debug/mapped_tag", qos_pub_once);
136+
detected_tag_pose_pub_ =
137+
this->create_publisher<PoseArray>("~/debug/detected_tag", qos_pub_periodic);
138+
diag_pub_ = this->create_publisher<DiagnosticArray>("/diagnostics", qos_pub_periodic);
151139

152140
RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!");
153-
return true;
154141
}
155142

156143
void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg)
157144
{
158145
landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger());
159146
const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg();
160-
marker_pub_->publish(marker_msg);
147+
mapped_tag_pose_pub_->publish(marker_msg);
161148
}
162149

163150
void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
164151
{
165152
// check subscribers
166-
if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) {
153+
if ((image_pub_->get_subscription_count() == 0) && (pose_pub_->get_subscription_count() == 0)) {
167154
RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers");
168155
return;
169156
}
@@ -192,7 +179,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
192179
}
193180

194181
// for debug
195-
if (pose_array_pub_->get_subscription_count() > 0) {
182+
if (detected_tag_pose_pub_->get_subscription_count() > 0) {
196183
PoseArray pose_array_msg;
197184
pose_array_msg.header.stamp = sensor_stamp;
198185
pose_array_msg.header.frame_id = "map";
@@ -201,7 +188,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
201188
tier4_autoware_utils::transformPose(landmark.pose, self_pose);
202189
pose_array_msg.poses.push_back(detected_marker_on_map);
203190
}
204-
pose_array_pub_->publish(pose_array_msg);
191+
detected_tag_pose_pub_->publish(pose_array_msg);
205192
}
206193

207194
// calc new_self_pose
@@ -267,24 +254,12 @@ void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & m
267254
return;
268255
}
269256

270-
cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0);
271-
camera_matrix.at<double>(0, 0) = msg->p[0];
272-
camera_matrix.at<double>(0, 1) = msg->p[1];
273-
camera_matrix.at<double>(0, 2) = msg->p[2];
274-
camera_matrix.at<double>(0, 3) = msg->p[3];
275-
camera_matrix.at<double>(1, 0) = msg->p[4];
276-
camera_matrix.at<double>(1, 1) = msg->p[5];
277-
camera_matrix.at<double>(1, 2) = msg->p[6];
278-
camera_matrix.at<double>(1, 3) = msg->p[7];
279-
camera_matrix.at<double>(2, 0) = msg->p[8];
280-
camera_matrix.at<double>(2, 1) = msg->p[9];
281-
camera_matrix.at<double>(2, 2) = msg->p[10];
282-
camera_matrix.at<double>(2, 3) = msg->p[11];
283-
284-
cv::Mat distortion_coeff(4, 1, CV_64FC1);
285-
for (int i = 0; i < 4; ++i) {
286-
distortion_coeff.at<double>(i, 0) = 0;
287-
}
257+
// copy camera matrix
258+
cv::Mat camera_matrix(3, 4, CV_64FC1);
259+
std::copy(msg->p.begin(), msg->p.end(), camera_matrix.begin<double>());
260+
261+
// all 0
262+
cv::Mat distortion_coeff(4, 1, CV_64FC1, 0.0);
288263

289264
const cv::Size size(static_cast<int>(msg->width), static_cast<int>(msg->height));
290265

@@ -361,12 +336,12 @@ std::vector<landmark_manager::Landmark> ArTagBasedLocalizer::detect_landmarks(
361336
}
362337

363338
// for debug
364-
if (image_pub_.getNumSubscribers() > 0) {
339+
if (image_pub_->get_subscription_count() > 0) {
365340
cv_bridge::CvImage out_msg;
366341
out_msg.header.stamp = sensor_stamp;
367342
out_msg.encoding = sensor_msgs::image_encodings::RGB8;
368343
out_msg.image = in_image;
369-
image_pub_.publish(out_msg.toImageMsg());
344+
image_pub_->publish(*out_msg.toImageMsg());
370345
}
371346

372347
return landmarks;

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp

+5-8
Original file line numberDiff line numberDiff line change
@@ -48,11 +48,12 @@
4848
#include "landmark_manager/landmark_manager.hpp"
4949
#include "localization_util/smart_pose_buffer.hpp"
5050

51-
#include <image_transport/image_transport.hpp>
5251
#include <rclcpp/rclcpp.hpp>
5352

5453
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
5554
#include <geometry_msgs/msg/pose_array.hpp>
55+
#include <sensor_msgs/msg/camera_info.hpp>
56+
#include <sensor_msgs/msg/image.hpp>
5657
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
5758
#include <visualization_msgs/msg/marker.hpp>
5859

@@ -82,7 +83,6 @@ class ArTagBasedLocalizer : public rclcpp::Node
8283

8384
public:
8485
explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
85-
bool setup();
8686

8787
private:
8888
void map_bin_callback(const HADMapBin::ConstSharedPtr & msg);
@@ -104,20 +104,17 @@ class ArTagBasedLocalizer : public rclcpp::Node
104104
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
105105
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
106106

107-
// image transport
108-
std::unique_ptr<image_transport::ImageTransport> it_;
109-
110107
// Subscribers
111108
rclcpp::Subscription<HADMapBin>::SharedPtr map_bin_sub_;
112109
rclcpp::Subscription<Image>::SharedPtr image_sub_;
113110
rclcpp::Subscription<CameraInfo>::SharedPtr cam_info_sub_;
114111
rclcpp::Subscription<PoseWithCovarianceStamped>::SharedPtr ekf_pose_sub_;
115112

116113
// Publishers
117-
rclcpp::Publisher<MarkerArray>::SharedPtr marker_pub_;
118-
rclcpp::Publisher<PoseArray>::SharedPtr pose_array_pub_;
119-
image_transport::Publisher image_pub_;
120114
rclcpp::Publisher<PoseWithCovarianceStamped>::SharedPtr pose_pub_;
115+
rclcpp::Publisher<Image>::SharedPtr image_pub_;
116+
rclcpp::Publisher<PoseArray>::SharedPtr detected_tag_pose_pub_;
117+
rclcpp::Publisher<MarkerArray>::SharedPtr mapped_tag_pose_pub_;
121118
rclcpp::Publisher<DiagnosticArray>::SharedPtr diag_pub_;
122119

123120
// Others

localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,6 @@ int main(int argc, char ** argv)
4848
{
4949
rclcpp::init(argc, argv);
5050
std::shared_ptr<ArTagBasedLocalizer> ptr = std::make_shared<ArTagBasedLocalizer>();
51-
ptr->setup();
5251
rclcpp::spin(ptr);
5352
rclcpp::shutdown();
5453
}

localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,8 @@ class TestArTagBasedLocalizer : public ::testing::Test
5555

5656
TEST_F(TestArTagBasedLocalizer, test_setup) // NOLINT
5757
{
58-
EXPECT_TRUE(node_->setup());
58+
// Check if the constructor finishes successfully
59+
EXPECT_TRUE(true);
5960
}
6061

6162
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)