Skip to content

Commit f321e40

Browse files
awf-autoware-bot[bot]kenji-miyakepre-commit-ci[bot]
authored
chore: sync files (autowarefoundation#3227)
* chore: sync files Signed-off-by: GitHub <noreply@github.com> * style(pre-commit): autofix --------- Signed-off-by: GitHub <noreply@github.com> Co-authored-by: kenji-miyake <kenji-miyake@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent ee72e08 commit f321e40

File tree

149 files changed

+1345
-344
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

149 files changed

+1345
-344
lines changed

.clang-format

+1
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@ BasedOnStyle: Google
44

55
AccessModifierOffset: -2
66
AlignAfterOpenBracket: AlwaysBreak
7+
AllowShortFunctionsOnASingleLine: InlineOnly
78
BraceWrapping:
89
AfterClass: true
910
AfterFunction: true

.github/PULL_REQUEST_TEMPLATE/small-change.md

+7
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,13 @@
22

33
<!-- Write a brief description of this PR. -->
44

5+
## Tests performed
6+
7+
<!-- Describe how you have tested this PR. -->
8+
<!-- Although the default value is set to "Not Applicable.", please update this section if the type is either [feat, fix, perf], or if requested by the reviewers. -->
9+
10+
Not applicable.
11+
512
## Pre-review checklist for the PR author
613

714
The PR author **must** check the checkboxes below when creating the PR.

.pre-commit-config.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ repos:
6060
- id: isort
6161

6262
- repo: https://github.com/psf/black
63-
rev: 23.1.0
63+
rev: 23.3.0
6464
hooks:
6565
- id: black
6666
args: [--line-length=100]

common/autoware_auto_geometry/src/spatial_hash.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,10 @@ details::Index3 Config2d::index3_(const float32_t x, const float32_t y, const fl
5959
return {x_index(x), y_index(y), Index{}}; // zero initialization
6060
}
6161
////////////////////////////////////////////////////////////////////////////////
62-
Index Config2d::index_(const details::Index3 & idx) const { return bin_impl(idx.x, idx.y); }
62+
Index Config2d::index_(const details::Index3 & idx) const
63+
{
64+
return bin_impl(idx.x, idx.y);
65+
}
6366
////////////////////////////////////////////////////////////////////////////////
6467
Config3d::Config3d(
6568
const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y,
@@ -88,7 +91,10 @@ details::Index3 Config3d::index3_(const float32_t x, const float32_t y, const fl
8891
return {x_index(x), y_index(y), z_index(z)}; // zero initialization
8992
}
9093
////////////////////////////////////////////////////////////////////////////////
91-
Index Config3d::index_(const details::Index3 & idx) const { return bin_impl(idx.x, idx.y, idx.z); }
94+
Index Config3d::index_(const details::Index3 & idx) const
95+
{
96+
return bin_impl(idx.x, idx.y, idx.z);
97+
}
9298
////////////////////////////////////////////////////////////////////////////////
9399
template class SpatialHash<geometry_msgs::msg::Point32, Config2d>;
94100
template class SpatialHash<geometry_msgs::msg::Point32, Config3d>;

common/autoware_auto_geometry/test/src/test_area.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,10 @@ using TestTypes = TestTypes_<geometry_msgs::msg::Point32>;
5353
TYPED_TEST_SUITE(AreaTest, TestTypes, );
5454

5555
// The empty set has zero area
56-
TYPED_TEST(AreaTest, DegenerateZero) { EXPECT_FLOAT_EQ(0.0, this->area()); }
56+
TYPED_TEST(AreaTest, DegenerateZero)
57+
{
58+
EXPECT_FLOAT_EQ(0.0, this->area());
59+
}
5760

5861
// An individual point has zero area
5962
TYPED_TEST(AreaTest, DegenerateOne)

common/autoware_auto_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,9 @@ namespace rviz_plugins
2424
{
2525
namespace object_detection
2626
{
27-
DetectedObjectsDisplay::DetectedObjectsDisplay() : ObjectPolygonDisplayBase("detected_objects") {}
27+
DetectedObjectsDisplay::DetectedObjectsDisplay() : ObjectPolygonDisplayBase("detected_objects")
28+
{
29+
}
2830

2931
void DetectedObjectsDisplay::processMessage(DetectedObjects::ConstSharedPtr msg)
3032
{

common/autoware_auto_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,9 @@ namespace rviz_plugins
2424
{
2525
namespace object_detection
2626
{
27-
TrackedObjectsDisplay::TrackedObjectsDisplay() : ObjectPolygonDisplayBase("tracks") {}
27+
TrackedObjectsDisplay::TrackedObjectsDisplay() : ObjectPolygonDisplayBase("tracks")
28+
{
29+
}
2830

2931
void TrackedObjectsDisplay::processMessage(TrackedObjects::ConstSharedPtr msg)
3032
{

common/fake_test_node/src/fake_test_node.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,10 @@ void detail::FakeNodeCore::set_up(const std::string & test_name)
5353
std::make_shared<tf2_ros::TransformListener>(m_tf_buffer, m_fake_node, kSpinThread);
5454
}
5555

56-
void detail::FakeNodeCore::tear_down() { (void)rclcpp::shutdown(); }
56+
void detail::FakeNodeCore::tear_down()
57+
{
58+
(void)rclcpp::shutdown();
59+
}
5760

5861
std::string detail::get_test_name(const ::testing::TestInfo * info)
5962
{
@@ -68,7 +71,10 @@ void FakeTestNode::SetUp()
6871
set_up(detail::get_test_name(::testing::UnitTest::GetInstance()->current_test_info()));
6972
}
7073

71-
void FakeTestNode::TearDown() { tear_down(); }
74+
void FakeTestNode::TearDown()
75+
{
76+
tear_down();
77+
}
7278

7379
} // namespace testing
7480
} // namespace tools

common/fake_test_node/test/test_fake_test_node.cpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -91,12 +91,18 @@ void run_test(int32_t value_in_message, FixtureT * fixture)
9191
} // namespace
9292

9393
/// @test Test that we can use a non-parametrized test.
94-
TEST_F(FakeNodeFixture, Test) { run_test(15, this); }
94+
TEST_F(FakeNodeFixture, Test)
95+
{
96+
run_test(15, this);
97+
}
9598

9699
INSTANTIATE_TEST_SUITE_P(
97100
FakeNodeFixtureTests, FakeNodeFixtureParametrized,
98101
// cppcheck-suppress syntaxError // cppcheck doesn't like the trailing comma.
99102
::testing::Values(-5, 0, 42));
100103

101104
/// @test Test that we can use a parametrized test.
102-
TEST_P(FakeNodeFixtureParametrized, Test) { run_test(GetParam(), this); }
105+
TEST_P(FakeNodeFixtureParametrized, Test)
106+
{
107+
run_test(GetParam(), this);
108+
}

common/grid_map_utils/src/polygon_iterator.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,10 @@ bool PolygonIterator::operator!=(const PolygonIterator & other) const
153153
return current_line_ != other.current_line_ || current_col_ != other.current_col_;
154154
}
155155

156-
const grid_map::Index & PolygonIterator::operator*() const { return current_index_; }
156+
const grid_map::Index & PolygonIterator::operator*() const
157+
{
158+
return current_index_;
159+
}
157160

158161
void PolygonIterator::goToNextLine()
159162
{

common/kalman_filter/src/kalman_filter.cpp

+46-12
Original file line numberDiff line numberDiff line change
@@ -14,15 +14,19 @@
1414

1515
#include "kalman_filter/kalman_filter.hpp"
1616

17-
KalmanFilter::KalmanFilter() {}
17+
KalmanFilter::KalmanFilter()
18+
{
19+
}
1820
KalmanFilter::KalmanFilter(
1921
const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B,
2022
const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R,
2123
const Eigen::MatrixXd & P)
2224
{
2325
init(x, A, B, C, Q, R, P);
2426
}
25-
KalmanFilter::~KalmanFilter() {}
27+
KalmanFilter::~KalmanFilter()
28+
{
29+
}
2630
bool KalmanFilter::init(
2731
const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B,
2832
const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R,
@@ -53,14 +57,38 @@ bool KalmanFilter::init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0)
5357
return true;
5458
}
5559

56-
void KalmanFilter::setA(const Eigen::MatrixXd & A) { A_ = A; }
57-
void KalmanFilter::setB(const Eigen::MatrixXd & B) { B_ = B; }
58-
void KalmanFilter::setC(const Eigen::MatrixXd & C) { C_ = C; }
59-
void KalmanFilter::setQ(const Eigen::MatrixXd & Q) { Q_ = Q; }
60-
void KalmanFilter::setR(const Eigen::MatrixXd & R) { R_ = R; }
61-
void KalmanFilter::getX(Eigen::MatrixXd & x) { x = x_; }
62-
void KalmanFilter::getP(Eigen::MatrixXd & P) { P = P_; }
63-
double KalmanFilter::getXelement(unsigned int i) { return x_(i); }
60+
void KalmanFilter::setA(const Eigen::MatrixXd & A)
61+
{
62+
A_ = A;
63+
}
64+
void KalmanFilter::setB(const Eigen::MatrixXd & B)
65+
{
66+
B_ = B;
67+
}
68+
void KalmanFilter::setC(const Eigen::MatrixXd & C)
69+
{
70+
C_ = C;
71+
}
72+
void KalmanFilter::setQ(const Eigen::MatrixXd & Q)
73+
{
74+
Q_ = Q;
75+
}
76+
void KalmanFilter::setR(const Eigen::MatrixXd & R)
77+
{
78+
R_ = R;
79+
}
80+
void KalmanFilter::getX(Eigen::MatrixXd & x)
81+
{
82+
x = x_;
83+
}
84+
void KalmanFilter::getP(Eigen::MatrixXd & P)
85+
{
86+
P = P_;
87+
}
88+
double KalmanFilter::getXelement(unsigned int i)
89+
{
90+
return x_(i);
91+
}
6492

6593
bool KalmanFilter::predict(
6694
const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q)
@@ -89,7 +117,10 @@ bool KalmanFilter::predict(
89117
const Eigen::MatrixXd x_next = A * x_ + B * u;
90118
return predict(x_next, A, Q);
91119
}
92-
bool KalmanFilter::predict(const Eigen::MatrixXd & u) { return predict(u, A_, B_, Q_); }
120+
bool KalmanFilter::predict(const Eigen::MatrixXd & u)
121+
{
122+
return predict(u, A_, B_, Q_);
123+
}
93124

94125
bool KalmanFilter::update(
95126
const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C,
@@ -121,4 +152,7 @@ bool KalmanFilter::update(
121152
const Eigen::MatrixXd y_pred = C * x_;
122153
return update(y, y_pred, C, R);
123154
}
124-
bool KalmanFilter::update(const Eigen::MatrixXd & y) { return update(y, C_, R_); }
155+
bool KalmanFilter::update(const Eigen::MatrixXd & y)
156+
{
157+
return update(y, C_, R_);
158+
}

common/kalman_filter/src/time_delay_kalman_filter.cpp

+11-3
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,9 @@
1414

1515
#include "kalman_filter/time_delay_kalman_filter.hpp"
1616

17-
TimeDelayKalmanFilter::TimeDelayKalmanFilter() {}
17+
TimeDelayKalmanFilter::TimeDelayKalmanFilter()
18+
{
19+
}
1820

1921
void TimeDelayKalmanFilter::init(
2022
const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0, const int max_delay_step)
@@ -32,9 +34,15 @@ void TimeDelayKalmanFilter::init(
3234
}
3335
}
3436

35-
Eigen::MatrixXd TimeDelayKalmanFilter::getLatestX() const { return x_.block(0, 0, dim_x_, 1); }
37+
Eigen::MatrixXd TimeDelayKalmanFilter::getLatestX() const
38+
{
39+
return x_.block(0, 0, dim_x_, 1);
40+
}
3641

37-
Eigen::MatrixXd TimeDelayKalmanFilter::getLatestP() const { return P_.block(0, 0, dim_x_, dim_x_); }
42+
Eigen::MatrixXd TimeDelayKalmanFilter::getLatestP() const
43+
{
44+
return P_.block(0, 0, dim_x_, dim_x_);
45+
}
3846

3947
bool TimeDelayKalmanFilter::predictWithDelay(
4048
const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q)

common/motion_utils/src/vehicle/vehicle_state_checker.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -128,5 +128,8 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati
128128
th_arrived_distance_m;
129129
}
130130

131-
void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg) { trajectory_ptr_ = msg; }
131+
void VehicleArrivalChecker::onTrajectory(const Trajectory::SharedPtr msg)
132+
{
133+
trajectory_ptr_ = msg;
134+
}
132135
} // namespace motion_utils

common/osqp_interface/src/osqp_interface.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -208,7 +208,10 @@ void OSQPInterface::updateAlpha(const double alpha)
208208
}
209209
}
210210

211-
void OSQPInterface::updateScaling(const int scaling) { m_settings->scaling = scaling; }
211+
void OSQPInterface::updateScaling(const int scaling)
212+
{
213+
m_settings->scaling = scaling;
214+
}
212215

213216
void OSQPInterface::updatePolish(const bool polish)
214217
{

common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp

+32-8
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,14 @@
2525

2626
namespace rviz_plugins
2727
{
28-
inline std::string Bool2String(const bool var) { return var ? "True" : "False"; }
29-
inline bool uint2bool(uint8_t var) { return var == static_cast<uint8_t>(0) ? false : true; }
28+
inline std::string Bool2String(const bool var)
29+
{
30+
return var ? "True" : "False";
31+
}
32+
inline bool uint2bool(uint8_t var)
33+
{
34+
return var == static_cast<uint8_t>(0) ? false : true;
35+
}
3036
using std::placeholders::_1;
3137
using std::placeholders::_2;
3238

@@ -326,12 +332,30 @@ void RTCManagerPanel::onClickCommandRequest(const uint8_t command)
326332
client_rtc_commands_->async_send_request(executable_cooperate_commands_request);
327333
}
328334

329-
void RTCManagerPanel::onClickExecuteVelChange() { onClickChangeRequest(false, Command::ACTIVATE); }
330-
void RTCManagerPanel::onClickWaitVelChange() { onClickChangeRequest(false, Command::DEACTIVATE); }
331-
void RTCManagerPanel::onClickExecutePathChange() { onClickChangeRequest(true, Command::ACTIVATE); }
332-
void RTCManagerPanel::onClickWaitPathChange() { onClickChangeRequest(true, Command::DEACTIVATE); }
333-
void RTCManagerPanel::onClickExecution() { onClickCommandRequest(Command::ACTIVATE); }
334-
void RTCManagerPanel::onClickWait() { onClickCommandRequest(Command::DEACTIVATE); }
335+
void RTCManagerPanel::onClickExecuteVelChange()
336+
{
337+
onClickChangeRequest(false, Command::ACTIVATE);
338+
}
339+
void RTCManagerPanel::onClickWaitVelChange()
340+
{
341+
onClickChangeRequest(false, Command::DEACTIVATE);
342+
}
343+
void RTCManagerPanel::onClickExecutePathChange()
344+
{
345+
onClickChangeRequest(true, Command::ACTIVATE);
346+
}
347+
void RTCManagerPanel::onClickWaitPathChange()
348+
{
349+
onClickChangeRequest(true, Command::DEACTIVATE);
350+
}
351+
void RTCManagerPanel::onClickExecution()
352+
{
353+
onClickCommandRequest(Command::ACTIVATE);
354+
}
355+
void RTCManagerPanel::onClickWait()
356+
{
357+
onClickCommandRequest(Command::DEACTIVATE);
358+
}
335359

336360
void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg)
337361
{

common/signal_processing/src/butterworth.cpp

+24-6
Original file line numberDiff line numberDiff line change
@@ -52,9 +52,15 @@ void ButterworthFilter::Buttord(
5252
setCutOffFrequency(right_lim);
5353
}
5454

55-
void ButterworthFilter::setOrder(const int & N) { filter_specs_.N = N; }
55+
void ButterworthFilter::setOrder(const int & N)
56+
{
57+
filter_specs_.N = N;
58+
}
5659

57-
void ButterworthFilter::setCutOffFrequency(const double & Wc) { filter_specs_.Wc_rad_sec = Wc; }
60+
void ButterworthFilter::setCutOffFrequency(const double & Wc)
61+
{
62+
filter_specs_.Wc_rad_sec = Wc;
63+
}
5864

5965
/**
6066
* @brief Sets the cut-off and sampling frequencies.
@@ -76,7 +82,10 @@ void ButterworthFilter::setCutOffFrequency(const double & fc, const double & fs)
7682
filter_specs_.fs = fs;
7783
}
7884

79-
sOrderCutOff ButterworthFilter::getOrderCutOff() const { return filter_specs_; }
85+
sOrderCutOff ButterworthFilter::getOrderCutOff() const
86+
{
87+
return filter_specs_;
88+
}
8089

8190
/**
8291
* @brief Matlab equivalent : [b, a] = butter(n, Wn, 's')
@@ -306,9 +315,18 @@ void ButterworthFilter::printDiscreteTimeTF() const
306315

307316
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "[%s]", stream.str().c_str());
308317
}
309-
std::vector<double> ButterworthFilter::getAn() const { return AnBn_.An; }
310-
std::vector<double> ButterworthFilter::getBn() const { return AnBn_.Bn; }
311-
sDifferenceAnBn ButterworthFilter::getAnBn() const { return AnBn_; }
318+
std::vector<double> ButterworthFilter::getAn() const
319+
{
320+
return AnBn_.An;
321+
}
322+
std::vector<double> ButterworthFilter::getBn() const
323+
{
324+
return AnBn_.Bn;
325+
}
326+
sDifferenceAnBn ButterworthFilter::getAnBn() const
327+
{
328+
return AnBn_;
329+
}
312330

313331
void ButterworthFilter::printFilterSpecs() const
314332
{

0 commit comments

Comments
 (0)