Skip to content

Commit 7eb1da5

Browse files
committed
refactor based on linter
Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>
1 parent 93a6abf commit 7eb1da5

File tree

2 files changed

+52
-47
lines changed

2 files changed

+52
-47
lines changed

sensing/gnss_poser/include/gnss_poser/gnss_poser_core.hpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -49,29 +49,29 @@ class GNSSPoser : public rclcpp::Node
4949
private:
5050
using MapProjectorInfo = map_interface::MapProjectorInfo;
5151

52-
void callbackMapProjectorInfo(const MapProjectorInfo::Message::ConstSharedPtr msg);
53-
void callbackNavSatFix(const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr);
54-
void callbackGnssInsOrientationStamped(
52+
void callback_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg);
53+
void callback_nav_sat_fix(const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr);
54+
void callback_gnss_ins_orientation_stamped(
5555
const autoware_sensing_msgs::msg::GnssInsOrientationStamped::ConstSharedPtr msg);
5656

57-
bool isFixed(const sensor_msgs::msg::NavSatStatus & nav_sat_status_msg);
58-
bool canGetCovariance(const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg);
59-
geometry_msgs::msg::Point getMedianPosition(
57+
static bool is_fixed(const sensor_msgs::msg::NavSatStatus & nav_sat_status_msg);
58+
static bool can_get_covariance(const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg);
59+
static geometry_msgs::msg::Point get_median_position(
6060
const boost::circular_buffer<geometry_msgs::msg::Point> & position_buffer);
61-
geometry_msgs::msg::Point getAveragePosition(
61+
static geometry_msgs::msg::Point get_average_position(
6262
const boost::circular_buffer<geometry_msgs::msg::Point> & position_buffer);
63-
geometry_msgs::msg::Quaternion getQuaternionByHeading(const int heading);
64-
geometry_msgs::msg::Quaternion getQuaternionByPositionDifference(
63+
static geometry_msgs::msg::Quaternion get_quaternion_by_heading(const int heading);
64+
static geometry_msgs::msg::Quaternion get_quaternion_by_position_difference(
6565
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Point & prev_point);
6666

67-
bool getTransform(
67+
bool get_transform(
6868
const std::string & target_frame, const std::string & source_frame,
6969
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr);
70-
bool getStaticTransform(
70+
bool get_static_transform(
7171
const std::string & target_frame, const std::string & source_frame,
7272
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr,
7373
const builtin_interfaces::msg::Time & stamp);
74-
void publishTF(
74+
void publish_tf(
7575
const std::string & frame_id, const std::string & child_frame_id,
7676
const geometry_msgs::msg::PoseStamped & pose_msg);
7777

@@ -99,7 +99,7 @@ class GNSSPoser : public rclcpp::Node
9999

100100
autoware_sensing_msgs::msg::GnssInsOrientationStamped::SharedPtr
101101
msg_gnss_ins_orientation_stamped_;
102-
int gnss_pose_pub_method;
102+
int gnss_pose_pub_method_;
103103
};
104104
} // namespace gnss_poser
105105

sensing/gnss_poser/src/gnss_poser_core.cpp

+39-34
Original file line numberDiff line numberDiff line change
@@ -36,25 +36,28 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
3636
use_gnss_ins_orientation_(declare_parameter<bool>("use_gnss_ins_orientation")),
3737
msg_gnss_ins_orientation_stamped_(
3838
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")))
4040
{
4141
// Subscribe to map_projector_info topic
4242
const auto adaptor = component_interface_utils::NodeAdaptor(this);
4343
adaptor.init_sub(
4444
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+
});
4648

4749
// 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"));
4951
position_buffer_.set_capacity(buff_epoch);
5052

5153
// Set subscribers and publishers
5254
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));
5457
autoware_orientation_sub_ =
5558
create_subscription<autoware_sensing_msgs::msg::GnssInsOrientationStamped>(
5659
"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));
5861

5962
pose_pub_ = create_publisher<geometry_msgs::msg::PoseStamped>("gnss_pose", rclcpp::QoS{1});
6063
pose_cov_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
@@ -68,13 +71,13 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
6871
msg_gnss_ins_orientation_stamped_->orientation.rmse_rotation_z = 1.0;
6972
}
7073

71-
void GNSSPoser::callbackMapProjectorInfo(const MapProjectorInfo::Message::ConstSharedPtr msg)
74+
void GNSSPoser::callback_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg)
7275
{
7376
projector_info_ = *msg;
7477
received_map_projector_info_ = true;
7578
}
7679

77-
void GNSSPoser::callbackNavSatFix(
80+
void GNSSPoser::callback_nav_sat_fix(
7881
const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr)
7982
{
8083
// Return immediately if map_projector_info has not been received yet.
@@ -94,15 +97,15 @@ void GNSSPoser::callbackNavSatFix(
9497
}
9598

9699
// 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);
98101

99102
// publish is_fixed topic
100103
tier4_debug_msgs::msg::BoolStamped is_fixed_msg;
101104
is_fixed_msg.stamp = this->now();
102-
is_fixed_msg.data = is_fixed;
105+
is_fixed_msg.data = is_status_fixed;
103106
fixed_pub_->publish(is_fixed_msg);
104107

105-
if (!is_fixed) {
108+
if (!is_status_fixed) {
106109
RCLCPP_WARN_STREAM_THROTTLE(
107110
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
108111
"Not Fixed Topic. Skipping Calculate.");
@@ -114,15 +117,16 @@ void GNSSPoser::callbackNavSatFix(
114117
gps_point.latitude = nav_sat_fix_msg_ptr->latitude;
115118
gps_point.longitude = nav_sat_fix_msg_ptr->longitude;
116119
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_);
118122
position.z = geography_utils::convert_height(
119123
position.z, gps_point.latitude, gps_point.longitude, MapProjectorInfo::Message::WGS84,
120124
projector_info_.vertical_datum);
121125

122126
geometry_msgs::msg::Pose gnss_antenna_pose{};
123127

124128
// publish pose immediately
125-
if (!gnss_pose_pub_method) {
129+
if (!gnss_pose_pub_method_) {
126130
gnss_antenna_pose.position = position;
127131
} else {
128132
// fill position buffer
@@ -134,8 +138,9 @@ void GNSSPoser::callbackNavSatFix(
134138
return;
135139
}
136140
// 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_);
139144
}
140145

141146
// calc gnss antenna orientation
@@ -144,7 +149,7 @@ void GNSSPoser::callbackNavSatFix(
144149
orientation = msg_gnss_ins_orientation_stamped_->orientation.orientation;
145150
} else {
146151
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);
148153
prev_position = gnss_antenna_pose.position;
149154
}
150155

@@ -157,7 +162,7 @@ void GNSSPoser::callbackNavSatFix(
157162
auto tf_gnss_antenna2base_link_msg_ptr = std::make_shared<geometry_msgs::msg::TransformStamped>();
158163

159164
const std::string gnss_frame = nav_sat_fix_msg_ptr->header.frame_id;
160-
getStaticTransform(
165+
get_static_transform(
161166
gnss_frame, base_frame_, tf_gnss_antenna2base_link_msg_ptr, nav_sat_fix_msg_ptr->header.stamp);
162167
tf2::Transform tf_gnss_antenna2base_link{};
163168
tf2::fromMsg(tf_gnss_antenna2base_link_msg_ptr->transform, tf_gnss_antenna2base_link);
@@ -179,11 +184,11 @@ void GNSSPoser::callbackNavSatFix(
179184
gnss_base_pose_cov_msg.header = gnss_base_pose_msg.header;
180185
gnss_base_pose_cov_msg.pose.pose = gnss_base_pose_msg.pose;
181186
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;
183188
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;
185190
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;
187192

188193
if (use_gnss_ins_orientation_) {
189194
gnss_base_pose_cov_msg.pose.covariance[7 * 3] =
@@ -201,30 +206,30 @@ void GNSSPoser::callbackNavSatFix(
201206
pose_cov_pub_->publish(gnss_base_pose_cov_msg);
202207

203208
// 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);
205210
}
206211

207-
void GNSSPoser::callbackGnssInsOrientationStamped(
212+
void GNSSPoser::callback_gnss_ins_orientation_stamped(
208213
const autoware_sensing_msgs::msg::GnssInsOrientationStamped::ConstSharedPtr msg)
209214
{
210215
*msg_gnss_ins_orientation_stamped_ = *msg;
211216
}
212217

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)
214219
{
215220
return nav_sat_status_msg.status >= sensor_msgs::msg::NavSatStatus::STATUS_FIX;
216221
}
217222

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)
219224
{
220225
return nav_sat_fix_msg.position_covariance_type >
221226
sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
222227
}
223228

224-
geometry_msgs::msg::Point GNSSPoser::getMedianPosition(
229+
geometry_msgs::msg::Point GNSSPoser::get_median_position(
225230
const boost::circular_buffer<geometry_msgs::msg::Point> & position_buffer)
226231
{
227-
auto getMedian = [](std::vector<double> array) {
232+
auto get_median = [](std::vector<double> array) {
228233
std::sort(std::begin(array), std::end(array));
229234
const size_t median_index = array.size() / 2;
230235
double median = (array.size() % 2)
@@ -243,13 +248,13 @@ geometry_msgs::msg::Point GNSSPoser::getMedianPosition(
243248
}
244249

245250
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);
249254
return median_point;
250255
}
251256

252-
geometry_msgs::msg::Point GNSSPoser::getAveragePosition(
257+
geometry_msgs::msg::Point GNSSPoser::get_average_position(
253258
const boost::circular_buffer<geometry_msgs::msg::Point> & position_buffer)
254259
{
255260
std::vector<double> array_x;
@@ -271,7 +276,7 @@ geometry_msgs::msg::Point GNSSPoser::getAveragePosition(
271276
return average_point;
272277
}
273278

274-
geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByHeading(const int heading)
279+
geometry_msgs::msg::Quaternion GNSSPoser::get_quaternion_by_heading(const int heading)
275280
{
276281
int heading_conv = 0;
277282
// 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
288293
return tf2::toMsg(quaternion);
289294
}
290295

291-
geometry_msgs::msg::Quaternion GNSSPoser::getQuaternionByPositionDifference(
296+
geometry_msgs::msg::Quaternion GNSSPoser::get_quaternion_by_position_difference(
292297
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Point & prev_point)
293298
{
294299
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(
297302
return tf2::toMsg(quaternion);
298303
}
299304

300-
bool GNSSPoser::getTransform(
305+
bool GNSSPoser::get_transform(
301306
const std::string & target_frame, const std::string & source_frame,
302307
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr)
303308
{
@@ -340,7 +345,7 @@ bool GNSSPoser::getTransform(
340345
return true;
341346
}
342347

343-
bool GNSSPoser::getStaticTransform(
348+
bool GNSSPoser::get_static_transform(
344349
const std::string & target_frame, const std::string & source_frame,
345350
const geometry_msgs::msg::TransformStamped::SharedPtr transform_stamped_ptr,
346351
const builtin_interfaces::msg::Time & stamp)
@@ -385,7 +390,7 @@ bool GNSSPoser::getStaticTransform(
385390
return true;
386391
}
387392

388-
void GNSSPoser::publishTF(
393+
void GNSSPoser::publish_tf(
389394
const std::string & frame_id, const std::string & child_frame_id,
390395
const geometry_msgs::msg::PoseStamped & pose_msg)
391396
{

0 commit comments

Comments
 (0)