Skip to content

Commit c367db2

Browse files
authored
Merge branch 'master' into master
2 parents b42d13a + 9ff84dc commit c367db2

File tree

10 files changed

+119
-97
lines changed

10 files changed

+119
-97
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3333

3434
using ControllerStateMsg =
35-
steering_controllers_library::SteeringControllersLibrary::AckermannControllerState;
35+
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
3636
using ControllerReferenceMsg =
3737
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;
3838

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3333

3434
using ControllerStateMsg =
35-
steering_controllers_library::SteeringControllersLibrary::AckermannControllerState;
35+
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
3636
using ControllerReferenceMsg =
3737
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;
3838

gpio_controllers/test/test_gpio_command_controller.cpp

Lines changed: 80 additions & 65 deletions
Large diffs are not rendered by default.

gps_sensor_broadcaster/test/test_gps_sensor_broadcaster.cpp

Lines changed: 29 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,13 @@ class GPSSensorBroadcasterTest : public ::testing::Test
6262

6363
~GPSSensorBroadcasterTest() { rclcpp::shutdown(); }
6464

65+
void SetUp()
66+
{
67+
gps_broadcaster_ = std::make_unique<gps_sensor_broadcaster::GPSSensorBroadcaster>();
68+
}
69+
70+
void TearDown() { gps_broadcaster_.reset(nullptr); }
71+
6572
template <
6673
semantic_components::GPSSensorOption sensor_option =
6774
semantic_components::GPSSensorOption::WithoutCovariance>
@@ -80,7 +87,7 @@ class GPSSensorBroadcasterTest : public ::testing::Test
8087
state_ifs.emplace_back(altitude_covariance_);
8188
}
8289

83-
gps_broadcaster_.assign_interfaces({}, std::move(state_ifs));
90+
gps_broadcaster_->assign_interfaces({}, std::move(state_ifs));
8491
}
8592

8693
sensor_msgs::msg::NavSatFix subscribe_and_get_message()
@@ -89,7 +96,7 @@ class GPSSensorBroadcasterTest : public ::testing::Test
8996
auto subscription = test_subscription_node.create_subscription<sensor_msgs::msg::NavSatFix>(
9097
"/test_gps_sensor_broadcaster/gps/fix", 10,
9198
[](const sensor_msgs::msg::NavSatFix::SharedPtr) {});
92-
gps_broadcaster_.update(rclcpp::Time{}, rclcpp::Duration::from_seconds(0));
99+
gps_broadcaster_->update(rclcpp::Time{}, rclcpp::Duration::from_seconds(0));
93100
wait_for(subscription);
94101

95102
rclcpp::MessageInfo msg_info;
@@ -115,21 +122,21 @@ class GPSSensorBroadcasterTest : public ::testing::Test
115122
hardware_interface::StateInterface altitude_covariance_{
116123
sensor_name_, "altitude_covariance", &sensor_values_[7]};
117124

118-
gps_sensor_broadcaster::GPSSensorBroadcaster gps_broadcaster_;
125+
std::unique_ptr<gps_sensor_broadcaster::GPSSensorBroadcaster> gps_broadcaster_;
119126
};
120127

121128
TEST_F(GPSSensorBroadcasterTest, whenNoParamsAreSetThenInitShouldFail)
122129
{
123-
const auto result = gps_broadcaster_.init(
130+
const auto result = gps_broadcaster_->init(
124131
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
125-
gps_broadcaster_.define_custom_node_options());
132+
gps_broadcaster_->define_custom_node_options());
126133
ASSERT_EQ(result, controller_interface::return_type::ERROR);
127134
}
128135

129136
TEST_F(GPSSensorBroadcasterTest, whenOnlySensorNameIsSetThenInitShouldFail)
130137
{
131138
const auto node_options = create_node_options_with_overriden_parameters({sensor_name_param_});
132-
const auto result = gps_broadcaster_.init(
139+
const auto result = gps_broadcaster_->init(
133140
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
134141
node_options);
135142
ASSERT_EQ(result, controller_interface::return_type::ERROR);
@@ -141,28 +148,30 @@ TEST_F(
141148
{
142149
const auto node_options =
143150
create_node_options_with_overriden_parameters({sensor_name_param_, frame_id_});
144-
const auto result = gps_broadcaster_.init(
151+
const auto result = gps_broadcaster_->init(
145152
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
146153
node_options);
147154
ASSERT_EQ(result, controller_interface::return_type::OK);
148155
ASSERT_EQ(
149-
gps_broadcaster_.on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
150-
ASSERT_EQ(gps_broadcaster_.on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
156+
gps_broadcaster_->on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
157+
ASSERT_EQ(
158+
gps_broadcaster_->on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
151159
}
152160

153161
TEST_F(
154162
GPSSensorBroadcasterTest, whenBroadcasterIsActiveShouldPublishNavSatMsgWithCovarianceSetToZero)
155163
{
156164
const auto node_options =
157165
create_node_options_with_overriden_parameters({sensor_name_param_, frame_id_});
158-
const auto result = gps_broadcaster_.init(
166+
const auto result = gps_broadcaster_->init(
159167
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
160168
node_options);
161169
ASSERT_EQ(result, controller_interface::return_type::OK);
162170
ASSERT_EQ(
163-
gps_broadcaster_.on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
171+
gps_broadcaster_->on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
164172
setup_gps_broadcaster();
165-
ASSERT_EQ(gps_broadcaster_.on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
173+
ASSERT_EQ(
174+
gps_broadcaster_->on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
166175

167176
const auto gps_msg = subscribe_and_get_message();
168177
EXPECT_EQ(gps_msg.header.frame_id, frame_id_.get_value<std::string>());
@@ -186,14 +195,15 @@ TEST_F(
186195
frame_id_,
187196
{"static_position_covariance",
188197
std::vector<double>{static_covariance.begin(), static_covariance.end()}}});
189-
const auto result = gps_broadcaster_.init(
198+
const auto result = gps_broadcaster_->init(
190199
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
191200
node_options);
192201
ASSERT_EQ(result, controller_interface::return_type::OK);
193202
ASSERT_EQ(
194-
gps_broadcaster_.on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
203+
gps_broadcaster_->on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
195204
setup_gps_broadcaster();
196-
ASSERT_EQ(gps_broadcaster_.on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
205+
ASSERT_EQ(
206+
gps_broadcaster_->on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
197207

198208
const auto gps_msg = subscribe_and_get_message();
199209
EXPECT_EQ(gps_msg.header.frame_id, frame_id_.get_value<std::string>());
@@ -213,14 +223,15 @@ TEST_F(
213223
{
214224
const auto node_options = create_node_options_with_overriden_parameters(
215225
{sensor_name_param_, frame_id_, {"read_covariance_from_interface", true}});
216-
const auto result = gps_broadcaster_.init(
226+
const auto result = gps_broadcaster_->init(
217227
"test_gps_sensor_broadcaster", ros2_control_test_assets::minimal_robot_urdf, 0, "",
218228
node_options);
219229
ASSERT_EQ(result, controller_interface::return_type::OK);
220230
ASSERT_EQ(
221-
gps_broadcaster_.on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
231+
gps_broadcaster_->on_configure(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
222232
setup_gps_broadcaster<semantic_components::GPSSensorOption::WithCovariance>();
223-
ASSERT_EQ(gps_broadcaster_.on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
233+
ASSERT_EQ(
234+
gps_broadcaster_->on_activate(rclcpp_lifecycle::State()), callback_return_type::SUCCESS);
224235

225236
const auto gps_msg = subscribe_and_get_message();
226237
EXPECT_EQ(gps_msg.header.frame_id, frame_id_.get_value<std::string>());

steering_controllers_library/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
2121
tf2
2222
tf2_msgs
2323
tf2_geometry_msgs
24-
ackermann_msgs
2524
)
2625

2726
find_package(ament_cmake REQUIRED)

steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,6 @@
2828
#include "realtime_tools/realtime_publisher.hpp"
2929

3030
// TODO(anyone): Replace with controller specific messages
31-
#include "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
3231
#include "control_msgs/msg/steering_controller_status.hpp"
3332
#include "geometry_msgs/msg/twist_stamped.hpp"
3433
#include "nav_msgs/msg/odometry.hpp"
@@ -71,11 +70,10 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
7170
controller_interface::return_type update_and_write_commands(
7271
const rclcpp::Time & time, const rclcpp::Duration & period) override;
7372

74-
using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped;
7573
using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
7674
using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
7775
using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
78-
using AckermannControllerState = control_msgs::msg::SteeringControllerStatus;
76+
using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;
7977

8078
protected:
8179
controller_interface::CallbackReturn set_interface_numbers(
@@ -110,10 +108,10 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
110108
/// Odometry:
111109
steering_odometry::SteeringOdometry odometry_;
112110

113-
AckermannControllerState published_state_;
111+
SteeringControllerStateMsg published_state_;
114112

115-
using ControllerStatePublisher = realtime_tools::RealtimePublisher<AckermannControllerState>;
116-
rclcpp::Publisher<AckermannControllerState>::SharedPtr controller_s_publisher_;
113+
using ControllerStatePublisher = realtime_tools::RealtimePublisher<SteeringControllerStateMsg>;
114+
rclcpp::Publisher<SteeringControllerStateMsg>::SharedPtr controller_s_publisher_;
117115
std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
118116

119117
// name constants for state interfaces

steering_controllers_library/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@
4040
<depend>tf2</depend>
4141
<depend>tf2_msgs</depend>
4242
<depend>tf2_geometry_msgs</depend>
43-
<depend>ackermann_msgs</depend>
4443

4544
<test_depend>ament_cmake_gmock</test_depend>
4645
<test_depend>controller_manager</test_depend>

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -426,7 +426,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
426426
try
427427
{
428428
// State publisher
429-
controller_s_publisher_ = get_node()->create_publisher<AckermannControllerState>(
429+
controller_s_publisher_ = get_node()->create_publisher<SteeringControllerStateMsg>(
430430
"~/controller_state", rclcpp::SystemDefaultsQoS());
431431
controller_state_publisher_ =
432432
std::make_unique<ControllerStatePublisher>(controller_s_publisher_);

steering_controllers_library/test/test_steering_controllers_library.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@
3232
#include "steering_controllers_library/steering_controllers_library.hpp"
3333

3434
using ControllerStateMsg =
35-
steering_controllers_library::SteeringControllersLibrary::AckermannControllerState;
36-
using ControllerTwistReferenceMsg =
35+
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
36+
using ControllerReferenceMsg =
3737
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;
3838
using ControllerAckermannReferenceMsg =
3939
steering_controllers_library::SteeringControllersLibrary::ControllerAckermannReferenceMsg;

tricycle_steering_controller/test/test_tricycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#include "tricycle_steering_controller/tricycle_steering_controller.hpp"
3333

3434
using ControllerStateMsg =
35-
steering_controllers_library::SteeringControllersLibrary::AckermannControllerState;
35+
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
3636
using ControllerReferenceMsg =
3737
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;
3838

0 commit comments

Comments
 (0)