@@ -72,11 +72,11 @@ void Lanelet2Overlay::on_image(const sensor_msgs::msg::Image & msg)
72
72
// Search synchronized pose
73
73
float min_abs_dt = std::numeric_limits<float >::max ();
74
74
std::optional<Pose> synched_pose{std::nullopt};
75
- for (auto pose : pose_buffer_) {
75
+ for (const auto & pose : pose_buffer_) {
76
76
auto dt = (rclcpp::Time (pose.header .stamp ) - stamp);
77
77
auto abs_dt = std::abs (dt.seconds ());
78
78
if (abs_dt < min_abs_dt) {
79
- min_abs_dt = abs_dt;
79
+ min_abs_dt = static_cast < float >( abs_dt) ;
80
80
synched_pose = pose.pose ;
81
81
}
82
82
}
@@ -93,19 +93,17 @@ void Lanelet2Overlay::on_line_segments(const PointCloud2 & msg)
93
93
// Search synchronized pose
94
94
float min_dt = std::numeric_limits<float >::max ();
95
95
geometry_msgs::msg::PoseStamped synched_pose;
96
- for (auto pose : pose_buffer_) {
96
+ for (const auto & pose : pose_buffer_) {
97
97
auto dt = (rclcpp::Time (pose.header .stamp ) - stamp);
98
98
auto abs_dt = std::abs (dt.seconds ());
99
99
if (abs_dt < min_dt) {
100
- min_dt = abs_dt;
100
+ min_dt = static_cast < float >( abs_dt) ;
101
101
synched_pose = pose;
102
102
}
103
103
}
104
104
if (min_dt > 0.1 ) return ;
105
105
auto latest_pose_stamp = rclcpp::Time (pose_buffer_.back ().header .stamp );
106
106
107
- std::vector<int > a;
108
-
109
107
LineSegments line_segments_cloud;
110
108
pcl::fromROSMsg (msg, line_segments_cloud);
111
109
make_vis_marker (line_segments_cloud, synched_pose.pose , stamp);
@@ -139,32 +137,35 @@ void Lanelet2Overlay::draw_overlay_line_segments(
139
137
if (!camera_extrinsic_.has_value ()) return ;
140
138
if (!info_.has_value ()) return ;
141
139
142
- Eigen::Matrix3f K =
140
+ Eigen::Matrix3f k =
143
141
Eigen::Map<Eigen::Matrix<double , 3 , 3 > >(info_->k .data ()).cast <float >().transpose ();
144
- Eigen::Affine3f T = camera_extrinsic_.value ();
142
+ Eigen::Affine3f t = camera_extrinsic_.value ();
145
143
146
144
Eigen::Affine3f transform = ground_plane_.align_with_slope (common::pose_to_affine (pose));
147
145
148
- auto projectLineSegment =
149
- [K, T , transform](
146
+ auto project_line_segment =
147
+ [k, t , transform](
150
148
const Eigen::Vector3f & p1,
151
149
const Eigen::Vector3f & p2) -> std::tuple<bool , cv::Point2i, cv::Point2i> {
152
- Eigen::Vector3f from_camera1 = K * T .inverse () * transform.inverse () * p1;
153
- Eigen::Vector3f from_camera2 = K * T .inverse () * transform.inverse () * p2;
154
- constexpr float EPSILON = 0 .1f ;
155
- bool p1_is_visible = from_camera1.z () > EPSILON ;
156
- bool p2_is_visible = from_camera2.z () > EPSILON ;
150
+ Eigen::Vector3f from_camera1 = k * t .inverse () * transform.inverse () * p1;
151
+ Eigen::Vector3f from_camera2 = k * t .inverse () * transform.inverse () * p2;
152
+ constexpr float epsilon = 0 .1f ;
153
+ bool p1_is_visible = from_camera1.z () > epsilon ;
154
+ bool p2_is_visible = from_camera2.z () > epsilon ;
157
155
if ((!p1_is_visible) && (!p2_is_visible)) return {false , cv::Point2i{}, cv::Point2i{}};
158
156
159
- Eigen::Vector3f uv1, uv2;
157
+ Eigen::Vector3f uv1;
158
+ Eigen::Vector3f uv2;
160
159
if (p1_is_visible) uv1 = from_camera1 / from_camera1.z ();
161
160
if (p2_is_visible) uv2 = from_camera2 / from_camera2.z ();
162
161
163
162
if ((p1_is_visible) && (p2_is_visible))
164
- return {true , cv::Point2i (uv1.x (), uv1.y ()), cv::Point2i (uv2.x (), uv2.y ())};
163
+ return {
164
+ true , cv::Point2i (static_cast <int >(uv1.x ()), static_cast <int >(uv1.y ())),
165
+ cv::Point2i (static_cast <int >(uv2.x ()), static_cast <int >(uv2.y ()))};
165
166
166
167
Eigen::Vector3f tangent = from_camera2 - from_camera1;
167
- float mu = (EPSILON - from_camera1.z ()) / (tangent.z ());
168
+ float mu = (epsilon - from_camera1.z ()) / (tangent.z ());
168
169
if (!p1_is_visible) {
169
170
from_camera1 = from_camera1 + mu * tangent;
170
171
uv1 = from_camera1 / from_camera1.z ();
@@ -173,11 +174,13 @@ void Lanelet2Overlay::draw_overlay_line_segments(
173
174
from_camera2 = from_camera1 + mu * tangent;
174
175
uv2 = from_camera2 / from_camera2.z ();
175
176
}
176
- return {true , cv::Point2i (uv1.x (), uv1.y ()), cv::Point2i (uv2.x (), uv2.y ())};
177
+ return {
178
+ true , cv::Point2i (static_cast <int >(uv1.x ()), static_cast <int >(uv1.y ())),
179
+ cv::Point2i (static_cast <int >(uv2.x ()), static_cast <int >(uv2.y ()))};
177
180
};
178
181
179
182
for (const pcl::PointNormal & pn : near_segments) {
180
- auto [success, u1, u2] = projectLineSegment (pn.getVector3fMap (), pn.getNormalVector3fMap ());
183
+ auto [success, u1, u2] = project_line_segment (pn.getVector3fMap (), pn.getNormalVector3fMap ());
181
184
if (success) cv::line (image, u1, u2, cv::Scalar (0 , 255 , 255 ), 2 );
182
185
}
183
186
}
@@ -197,7 +200,8 @@ void Lanelet2Overlay::make_vis_marker(
197
200
marker.color .a = 0 .7f ;
198
201
199
202
for (const auto pn : ls) {
200
- geometry_msgs::msg::Point p1, p2;
203
+ geometry_msgs::msg::Point p1;
204
+ geometry_msgs::msg::Point p2;
201
205
p1.x = pn.x ;
202
206
p1.y = pn.y ;
203
207
p1.z = pn.z ;
0 commit comments