66
66
67
67
ArTagBasedLocalizer::ArTagBasedLocalizer (const rclcpp::NodeOptions & options)
68
68
: Node(" ar_tag_based_localizer" , options), cam_info_received_(false )
69
- {
70
- }
71
-
72
- bool ArTagBasedLocalizer::setup ()
73
69
{
74
70
/*
75
71
Declare node parameters
@@ -92,7 +88,7 @@ bool ArTagBasedLocalizer::setup()
92
88
} else {
93
89
// Error
94
90
RCLCPP_ERROR_STREAM (this ->get_logger (), " Invalid detection_mode: " << detection_mode);
95
- return false ;
91
+ return ;
96
92
}
97
93
ekf_pose_buffer_ = std::make_unique<SmartPoseBuffer>(
98
94
this ->get_logger (), ekf_time_tolerance_, ekf_position_tolerance_);
@@ -111,59 +107,50 @@ bool ArTagBasedLocalizer::setup()
111
107
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this ->get_clock ());
112
108
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
113
109
114
- /*
115
- Initialize image transport
116
- */
117
- it_ = std::make_unique<image_transport::ImageTransport>(shared_from_this ());
118
-
119
110
/*
120
111
Subscribers
121
112
*/
113
+ using std::placeholders::_1;
122
114
map_bin_sub_ = this ->create_subscription <HADMapBin>(
123
115
" ~/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));
125
117
126
118
rclcpp::QoS qos_sub (rclcpp::QoSInitialization::from_rmw (rmw_qos_profile_default));
127
119
qos_sub.best_effort ();
128
- pose_array_pub_ = this ->create_publisher <PoseArray>(" ~/debug/detected_landmarks" , qos_sub);
129
120
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));
132
122
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));
135
124
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));
138
126
139
127
/*
140
128
Publishers
141
129
*/
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 );
151
139
152
140
RCLCPP_INFO (this ->get_logger (), " Setup of ar_tag_based_localizer node is successful!" );
153
- return true ;
154
141
}
155
142
156
143
void ArTagBasedLocalizer::map_bin_callback (const HADMapBin::ConstSharedPtr & msg)
157
144
{
158
145
landmark_manager_.parse_landmarks (msg, " apriltag_16h5" , this ->get_logger ());
159
146
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);
161
148
}
162
149
163
150
void ArTagBasedLocalizer::image_callback (const Image::ConstSharedPtr & msg)
164
151
{
165
152
// 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 )) {
167
154
RCLCPP_DEBUG (this ->get_logger (), " No subscribers, not looking for ArUco markers" );
168
155
return ;
169
156
}
@@ -192,7 +179,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
192
179
}
193
180
194
181
// for debug
195
- if (pose_array_pub_ ->get_subscription_count () > 0 ) {
182
+ if (detected_tag_pose_pub_ ->get_subscription_count () > 0 ) {
196
183
PoseArray pose_array_msg;
197
184
pose_array_msg.header .stamp = sensor_stamp;
198
185
pose_array_msg.header .frame_id = " map" ;
@@ -201,7 +188,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
201
188
tier4_autoware_utils::transformPose (landmark.pose , self_pose);
202
189
pose_array_msg.poses .push_back (detected_marker_on_map);
203
190
}
204
- pose_array_pub_ ->publish (pose_array_msg);
191
+ detected_tag_pose_pub_ ->publish (pose_array_msg);
205
192
}
206
193
207
194
// calc new_self_pose
@@ -267,24 +254,12 @@ void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & m
267
254
return ;
268
255
}
269
256
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 );
288
263
289
264
const cv::Size size (static_cast <int >(msg->width ), static_cast <int >(msg->height ));
290
265
@@ -361,12 +336,12 @@ std::vector<landmark_manager::Landmark> ArTagBasedLocalizer::detect_landmarks(
361
336
}
362
337
363
338
// for debug
364
- if (image_pub_. getNumSubscribers () > 0 ) {
339
+ if (image_pub_-> get_subscription_count () > 0 ) {
365
340
cv_bridge::CvImage out_msg;
366
341
out_msg.header .stamp = sensor_stamp;
367
342
out_msg.encoding = sensor_msgs::image_encodings::RGB8;
368
343
out_msg.image = in_image;
369
- image_pub_. publish (out_msg.toImageMsg ());
344
+ image_pub_-> publish (* out_msg.toImageMsg ());
370
345
}
371
346
372
347
return landmarks;
0 commit comments