@@ -36,25 +36,28 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
36
36
use_gnss_ins_orientation_(declare_parameter<bool >(" use_gnss_ins_orientation" )),
37
37
msg_gnss_ins_orientation_stamped_(
38
38
std::make_shared<autoware_sensing_msgs::msg::GnssInsOrientationStamped>()),
39
- gnss_pose_pub_method( declare_parameter<int >(" gnss_pose_pub_method" ))
39
+ gnss_pose_pub_method_( static_cast < int >( declare_parameter<int >(" gnss_pose_pub_method" ) ))
40
40
{
41
41
// Subscribe to map_projector_info topic
42
42
const auto adaptor = component_interface_utils::NodeAdaptor (this );
43
43
adaptor.init_sub (
44
44
sub_map_projector_info_,
45
- [this ](const MapProjectorInfo::Message::ConstSharedPtr msg) { callbackMapProjectorInfo (msg); });
45
+ [this ](const MapProjectorInfo::Message::ConstSharedPtr msg) {
46
+ callback_map_projector_info (msg);
47
+ });
46
48
47
49
// Set up position buffer
48
- int buff_epoch = declare_parameter<int >(" buff_epoch" );
50
+ int buff_epoch = static_cast < int >( declare_parameter<int >(" buff_epoch" ) );
49
51
position_buffer_.set_capacity (buff_epoch);
50
52
51
53
// Set subscribers and publishers
52
54
nav_sat_fix_sub_ = create_subscription<sensor_msgs::msg::NavSatFix>(
53
- " fix" , rclcpp::QoS{1 }, std::bind (&GNSSPoser::callbackNavSatFix, this , std::placeholders::_1));
55
+ " fix" , rclcpp::QoS{1 },
56
+ std::bind (&GNSSPoser::callback_nav_sat_fix, this , std::placeholders::_1));
54
57
autoware_orientation_sub_ =
55
58
create_subscription<autoware_sensing_msgs::msg::GnssInsOrientationStamped>(
56
59
" autoware_orientation" , rclcpp::QoS{1 },
57
- std::bind (&GNSSPoser::callbackGnssInsOrientationStamped , this , std::placeholders::_1));
60
+ std::bind (&GNSSPoser::callback_gnss_ins_orientation_stamped , this , std::placeholders::_1));
58
61
59
62
pose_pub_ = create_publisher<geometry_msgs::msg::PoseStamped>(" gnss_pose" , rclcpp::QoS{1 });
60
63
pose_cov_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
@@ -68,13 +71,13 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
68
71
msg_gnss_ins_orientation_stamped_->orientation .rmse_rotation_z = 1.0 ;
69
72
}
70
73
71
- void GNSSPoser::callbackMapProjectorInfo (const MapProjectorInfo::Message::ConstSharedPtr msg)
74
+ void GNSSPoser::callback_map_projector_info (const MapProjectorInfo::Message::ConstSharedPtr msg)
72
75
{
73
76
projector_info_ = *msg;
74
77
received_map_projector_info_ = true ;
75
78
}
76
79
77
- void GNSSPoser::callbackNavSatFix (
80
+ void GNSSPoser::callback_nav_sat_fix (
78
81
const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr)
79
82
{
80
83
// Return immediately if map_projector_info has not been received yet.
@@ -94,15 +97,15 @@ void GNSSPoser::callbackNavSatFix(
94
97
}
95
98
96
99
// check fixed topic
97
- const bool is_fixed = isFixed (nav_sat_fix_msg_ptr->status );
100
+ const bool is_status_fixed = is_fixed (nav_sat_fix_msg_ptr->status );
98
101
99
102
// publish is_fixed topic
100
103
tier4_debug_msgs::msg::BoolStamped is_fixed_msg;
101
104
is_fixed_msg.stamp = this ->now ();
102
- is_fixed_msg.data = is_fixed ;
105
+ is_fixed_msg.data = is_status_fixed ;
103
106
fixed_pub_->publish (is_fixed_msg);
104
107
105
- if (!is_fixed ) {
108
+ if (!is_status_fixed ) {
106
109
RCLCPP_WARN_STREAM_THROTTLE (
107
110
this ->get_logger (), *this ->get_clock (), std::chrono::milliseconds (1000 ).count (),
108
111
" Not Fixed Topic. Skipping Calculate." );
@@ -114,15 +117,16 @@ void GNSSPoser::callbackNavSatFix(
114
117
gps_point.latitude = nav_sat_fix_msg_ptr->latitude ;
115
118
gps_point.longitude = nav_sat_fix_msg_ptr->longitude ;
116
119
gps_point.altitude = nav_sat_fix_msg_ptr->altitude ;
117
- geometry_msgs::msg::Point position = geography_utils::project_forward (gps_point, projector_info_);
120
+ geometry_msgs::msg::Point position =
121
+ geography_utils::project_forward (gps_point, projector_info_);
118
122
position.z = geography_utils::convert_height (
119
123
position.z , gps_point.latitude , gps_point.longitude , MapProjectorInfo::Message::WGS84,
120
124
projector_info_.vertical_datum );
121
125
122
126
geometry_msgs::msg::Pose gnss_antenna_pose{};
123
127
124
128
// publish pose immediately
125
- if (!gnss_pose_pub_method ) {
129
+ if (!gnss_pose_pub_method_ ) {
126
130
gnss_antenna_pose.position = position;
127
131
} else {
128
132
// fill position buffer
@@ -134,8 +138,9 @@ void GNSSPoser::callbackNavSatFix(
134
138
return ;
135
139
}
136
140
// publish average pose or median pose of position buffer
137
- gnss_antenna_pose.position = (gnss_pose_pub_method == 1 ) ? getAveragePosition (position_buffer_)
138
- : getMedianPosition (position_buffer_);
141
+ gnss_antenna_pose.position =
142
+ (gnss_pose_pub_method_ == 1 ) ? get_average_position (position_buffer_)
143
+ : get_median_position (position_buffer_);
139
144
}
140
145
141
146
// calc gnss antenna orientation
@@ -144,7 +149,7 @@ void GNSSPoser::callbackNavSatFix(
144
149
orientation = msg_gnss_ins_orientation_stamped_->orientation .orientation ;
145
150
} else {
146
151
static auto prev_position = gnss_antenna_pose.position ;
147
- orientation = getQuaternionByPositionDifference (gnss_antenna_pose.position , prev_position);
152
+ orientation = get_quaternion_by_position_difference (gnss_antenna_pose.position , prev_position);
148
153
prev_position = gnss_antenna_pose.position ;
149
154
}
150
155
@@ -157,7 +162,7 @@ void GNSSPoser::callbackNavSatFix(
157
162
auto tf_gnss_antenna2base_link_msg_ptr = std::make_shared<geometry_msgs::msg::TransformStamped>();
158
163
159
164
const std::string gnss_frame = nav_sat_fix_msg_ptr->header .frame_id ;
160
- getStaticTransform (
165
+ get_static_transform (
161
166
gnss_frame, base_frame_, tf_gnss_antenna2base_link_msg_ptr, nav_sat_fix_msg_ptr->header .stamp );
162
167
tf2::Transform tf_gnss_antenna2base_link{};
163
168
tf2::fromMsg (tf_gnss_antenna2base_link_msg_ptr->transform , tf_gnss_antenna2base_link);
@@ -179,11 +184,11 @@ void GNSSPoser::callbackNavSatFix(
179
184
gnss_base_pose_cov_msg.header = gnss_base_pose_msg.header ;
180
185
gnss_base_pose_cov_msg.pose .pose = gnss_base_pose_msg.pose ;
181
186
gnss_base_pose_cov_msg.pose .covariance [7 * 0 ] =
182
- canGetCovariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [0 ] : 10.0 ;
187
+ can_get_covariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [0 ] : 10.0 ;
183
188
gnss_base_pose_cov_msg.pose .covariance [7 * 1 ] =
184
- canGetCovariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [4 ] : 10.0 ;
189
+ can_get_covariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [4 ] : 10.0 ;
185
190
gnss_base_pose_cov_msg.pose .covariance [7 * 2 ] =
186
- canGetCovariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [8 ] : 10.0 ;
191
+ can_get_covariance (*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance [8 ] : 10.0 ;
187
192
188
193
if (use_gnss_ins_orientation_) {
189
194
gnss_base_pose_cov_msg.pose .covariance [7 * 3 ] =
@@ -201,30 +206,30 @@ void GNSSPoser::callbackNavSatFix(
201
206
pose_cov_pub_->publish (gnss_base_pose_cov_msg);
202
207
203
208
// broadcast map to gnss_base_link
204
- publishTF (map_frame_, gnss_base_frame_, gnss_base_pose_msg);
209
+ publish_tf (map_frame_, gnss_base_frame_, gnss_base_pose_msg);
205
210
}
206
211
207
- void GNSSPoser::callbackGnssInsOrientationStamped (
212
+ void GNSSPoser::callback_gnss_ins_orientation_stamped (
208
213
const autoware_sensing_msgs::msg::GnssInsOrientationStamped::ConstSharedPtr msg)
209
214
{
210
215
*msg_gnss_ins_orientation_stamped_ = *msg;
211
216
}
212
217
213
- bool GNSSPoser::isFixed (const sensor_msgs::msg::NavSatStatus & nav_sat_status_msg)
218
+ bool GNSSPoser::is_fixed (const sensor_msgs::msg::NavSatStatus & nav_sat_status_msg)
214
219
{
215
220
return nav_sat_status_msg.status >= sensor_msgs::msg::NavSatStatus::STATUS_FIX;
216
221
}
217
222
218
- bool GNSSPoser::canGetCovariance (const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg)
223
+ bool GNSSPoser::can_get_covariance (const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg)
219
224
{
220
225
return nav_sat_fix_msg.position_covariance_type >
221
226
sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
222
227
}
223
228
224
- geometry_msgs::msg::Point GNSSPoser::getMedianPosition (
229
+ geometry_msgs::msg::Point GNSSPoser::get_median_position (
225
230
const boost::circular_buffer<geometry_msgs::msg::Point > & position_buffer)
226
231
{
227
- auto getMedian = [](std::vector<double > array) {
232
+ auto get_median = [](std::vector<double > array) {
228
233
std::sort (std::begin (array), std::end (array));
229
234
const size_t median_index = array.size () / 2 ;
230
235
double median = (array.size () % 2 )
@@ -243,13 +248,13 @@ geometry_msgs::msg::Point GNSSPoser::getMedianPosition(
243
248
}
244
249
245
250
geometry_msgs::msg::Point median_point;
246
- median_point.x = getMedian (array_x);
247
- median_point.y = getMedian (array_y);
248
- median_point.z = getMedian (array_z);
251
+ median_point.x = get_median (array_x);
252
+ median_point.y = get_median (array_y);
253
+ median_point.z = get_median (array_z);
249
254
return median_point;
250
255
}
251
256
252
- geometry_msgs::msg::Point GNSSPoser::getAveragePosition (
257
+ geometry_msgs::msg::Point GNSSPoser::get_average_position (
253
258
const boost::circular_buffer<geometry_msgs::msg::Point > & position_buffer)
254
259
{
255
260
std::vector<double > array_x;
@@ -271,7 +276,7 @@ geometry_msgs::msg::Point GNSSPoser::getAveragePosition(
271
276
return average_point;
272
277
}
273
278
274
- geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByHeading (const int heading)
279
+ geometry_msgs::msg::Quaternion GNSSPoser::get_quaternion_by_heading (const int heading)
275
280
{
276
281
int heading_conv = 0 ;
277
282
// convert heading[0(North)~360] to yaw[-M_PI(West)~M_PI]
@@ -288,7 +293,7 @@ geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByHeading(const int headi
288
293
return tf2::toMsg (quaternion);
289
294
}
290
295
291
- geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByPositionDifference (
296
+ geometry_msgs::msg::Quaternion GNSSPoser::get_quaternion_by_position_difference (
292
297
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Point & prev_point)
293
298
{
294
299
const double yaw = std::atan2 (point.y - prev_point.y , point.x - prev_point.x );
@@ -297,7 +302,7 @@ geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByPositionDifference(
297
302
return tf2::toMsg (quaternion);
298
303
}
299
304
300
- bool GNSSPoser::getTransform (
305
+ bool GNSSPoser::get_transform (
301
306
const std::string & target_frame, const std::string & source_frame,
302
307
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr)
303
308
{
@@ -340,7 +345,7 @@ bool GNSSPoser::getTransform(
340
345
return true ;
341
346
}
342
347
343
- bool GNSSPoser::getStaticTransform (
348
+ bool GNSSPoser::get_static_transform (
344
349
const std::string & target_frame, const std::string & source_frame,
345
350
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr,
346
351
const builtin_interfaces::msg::Time & stamp)
@@ -385,7 +390,7 @@ bool GNSSPoser::getStaticTransform(
385
390
return true ;
386
391
}
387
392
388
- void GNSSPoser::publishTF (
393
+ void GNSSPoser::publish_tf (
389
394
const std::string & frame_id, const std::string & child_frame_id,
390
395
const geometry_msgs::msg::PoseStamped & pose_msg)
391
396
{
0 commit comments