Skip to content

Commit be8092a

Browse files
Remove deprecated methods from ros2_control (#1936)
1 parent e1706a3 commit be8092a

File tree

41 files changed

+821
-704
lines changed

Some content is hidden

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

41 files changed

+821
-704
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 23 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -146,63 +146,63 @@ class AckermannSteeringControllerFixture : public ::testing::Test
146146
traction_interface_name_ = "velocity";
147147
}
148148

149-
std::vector<hardware_interface::LoanedCommandInterface> command_ifs;
149+
std::vector<hardware_interface::LoanedCommandInterface> loaned_command_ifs;
150150
command_itfs_.reserve(joint_command_values_.size());
151-
command_ifs.reserve(joint_command_values_.size());
151+
loaned_command_ifs.reserve(joint_command_values_.size());
152152

153153
command_itfs_.emplace_back(
154-
hardware_interface::CommandInterface(
154+
std::make_shared<hardware_interface::CommandInterface>(
155155
traction_joints_names_[0], traction_interface_name_,
156156
&joint_command_values_[CMD_TRACTION_RIGHT_WHEEL]));
157-
command_ifs.emplace_back(command_itfs_.back());
157+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
158158

159159
command_itfs_.emplace_back(
160-
hardware_interface::CommandInterface(
160+
std::make_shared<hardware_interface::CommandInterface>(
161161
traction_joints_names_[1], steering_interface_name_,
162162
&joint_command_values_[CMD_TRACTION_LEFT_WHEEL]));
163-
command_ifs.emplace_back(command_itfs_.back());
163+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
164164

165165
command_itfs_.emplace_back(
166-
hardware_interface::CommandInterface(
166+
std::make_shared<hardware_interface::CommandInterface>(
167167
steering_joints_names_[0], steering_interface_name_,
168168
&joint_command_values_[CMD_STEER_RIGHT_WHEEL]));
169-
command_ifs.emplace_back(command_itfs_.back());
169+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
170170

171171
command_itfs_.emplace_back(
172-
hardware_interface::CommandInterface(
172+
std::make_shared<hardware_interface::CommandInterface>(
173173
steering_joints_names_[1], steering_interface_name_,
174174
&joint_command_values_[CMD_STEER_LEFT_WHEEL]));
175-
command_ifs.emplace_back(command_itfs_.back());
175+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
176176

177-
std::vector<hardware_interface::LoanedStateInterface> state_ifs;
177+
std::vector<hardware_interface::LoanedStateInterface> loaned_state_ifs;
178178
state_itfs_.reserve(joint_state_values_.size());
179-
state_ifs.reserve(joint_state_values_.size());
179+
loaned_state_ifs.reserve(joint_state_values_.size());
180180

181181
state_itfs_.emplace_back(
182-
hardware_interface::StateInterface(
182+
std::make_shared<hardware_interface::StateInterface>(
183183
traction_joints_names_[0], traction_interface_name_,
184184
&joint_state_values_[STATE_TRACTION_RIGHT_WHEEL]));
185-
state_ifs.emplace_back(state_itfs_.back());
185+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
186186

187187
state_itfs_.emplace_back(
188-
hardware_interface::StateInterface(
188+
std::make_shared<hardware_interface::StateInterface>(
189189
traction_joints_names_[1], traction_interface_name_,
190190
&joint_state_values_[STATE_TRACTION_LEFT_WHEEL]));
191-
state_ifs.emplace_back(state_itfs_.back());
191+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
192192

193193
state_itfs_.emplace_back(
194-
hardware_interface::StateInterface(
194+
std::make_shared<hardware_interface::StateInterface>(
195195
steering_joints_names_[0], steering_interface_name_,
196196
&joint_state_values_[STATE_STEER_RIGHT_WHEEL]));
197-
state_ifs.emplace_back(state_itfs_.back());
197+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
198198

199199
state_itfs_.emplace_back(
200-
hardware_interface::StateInterface(
200+
std::make_shared<hardware_interface::StateInterface>(
201201
steering_joints_names_[1], steering_interface_name_,
202202
&joint_state_values_[STATE_STEER_LEFT_WHEEL]));
203-
state_ifs.emplace_back(state_itfs_.back());
203+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
204204

205-
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));
205+
controller_->assign_interfaces(std::move(loaned_command_ifs), std::move(loaned_state_ifs));
206206
}
207207

208208
void subscribe_and_get_messages(ControllerStateMsg & msg)
@@ -305,8 +305,8 @@ class AckermannSteeringControllerFixture : public ::testing::Test
305305
std::string traction_interface_name_ = "";
306306
std::string preceding_prefix_ = "pid_controller";
307307

308-
std::vector<hardware_interface::StateInterface> state_itfs_;
309-
std::vector<hardware_interface::CommandInterface> command_itfs_;
308+
std::vector<hardware_interface::StateInterface::SharedPtr> state_itfs_;
309+
std::vector<hardware_interface::CommandInterface::SharedPtr> command_itfs_;
310310

311311
// Test related parameters
312312
std::unique_ptr<TestableAckermannSteeringController> controller_;

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -171,32 +171,32 @@ class AdmittanceControllerTest : public ::testing::Test
171171

172172
void assign_interfaces()
173173
{
174-
std::vector<hardware_interface::LoanedCommandInterface> command_ifs;
174+
std::vector<hardware_interface::LoanedCommandInterface> loaned_command_ifs;
175175
command_itfs_.reserve(joint_command_values_.size());
176-
command_ifs.reserve(joint_command_values_.size());
176+
loaned_command_ifs.reserve(joint_command_values_.size());
177177

178178
for (auto i = 0u; i < joint_command_values_.size(); ++i)
179179
{
180180
command_itfs_.emplace_back(
181-
hardware_interface::CommandInterface(
181+
std::make_shared<hardware_interface::CommandInterface>(
182182
joint_names_[i], command_interface_types_[0], &joint_command_values_[i]));
183-
command_ifs.emplace_back(command_itfs_.back());
183+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
184184
}
185185

186186
auto sc_fts = semantic_components::ForceTorqueSensor(ft_sensor_name_);
187187
fts_state_names_ = sc_fts.get_state_interface_names();
188-
std::vector<hardware_interface::LoanedStateInterface> state_ifs;
188+
std::vector<hardware_interface::LoanedStateInterface> loaned_state_ifs;
189189

190190
const size_t num_state_ifs = joint_state_values_.size() + fts_state_names_.size();
191191
state_itfs_.reserve(num_state_ifs);
192-
state_ifs.reserve(num_state_ifs);
192+
loaned_state_ifs.reserve(num_state_ifs);
193193

194194
for (auto i = 0u; i < joint_state_values_.size(); ++i)
195195
{
196196
state_itfs_.emplace_back(
197-
hardware_interface::StateInterface(
197+
std::make_shared<hardware_interface::StateInterface>(
198198
joint_names_[i], state_interface_types_[0], &joint_state_values_[i]));
199-
state_ifs.emplace_back(state_itfs_.back());
199+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
200200
}
201201

202202
std::vector<std::string> fts_itf_names = {"force.x", "force.y", "force.z",
@@ -205,12 +205,12 @@ class AdmittanceControllerTest : public ::testing::Test
205205
for (auto i = 0u; i < fts_state_names_.size(); ++i)
206206
{
207207
state_itfs_.emplace_back(
208-
hardware_interface::StateInterface(
208+
std::make_shared<hardware_interface::StateInterface>(
209209
ft_sensor_name_, fts_itf_names[i], &fts_state_values_[i]));
210-
state_ifs.emplace_back(state_itfs_.back());
210+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
211211
}
212212

213-
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));
213+
controller_->assign_interfaces(std::move(loaned_command_ifs), std::move(loaned_state_ifs));
214214
}
215215

216216
void broadcast_tfs()
@@ -386,8 +386,8 @@ class AdmittanceControllerTest : public ::testing::Test
386386
std::array<double, 6> fts_state_values_ = {{0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
387387
std::vector<std::string> fts_state_names_;
388388

389-
std::vector<hardware_interface::StateInterface> state_itfs_;
390-
std::vector<hardware_interface::CommandInterface> command_itfs_;
389+
std::vector<hardware_interface::StateInterface::SharedPtr> state_itfs_;
390+
std::vector<hardware_interface::CommandInterface::SharedPtr> command_itfs_;
391391

392392
// Test related parameters
393393
std::unique_ptr<TestableAdmittanceController> controller_;

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -144,39 +144,39 @@ class BicycleSteeringControllerFixture : public ::testing::Test
144144
traction_interface_name_ = "velocity";
145145
}
146146

147-
std::vector<hardware_interface::LoanedCommandInterface> command_ifs;
147+
std::vector<hardware_interface::LoanedCommandInterface> loaned_command_ifs;
148148
command_itfs_.reserve(joint_command_values_.size());
149-
command_ifs.reserve(joint_command_values_.size());
149+
loaned_command_ifs.reserve(joint_command_values_.size());
150150

151151
command_itfs_.emplace_back(
152-
hardware_interface::CommandInterface(
152+
std::make_shared<hardware_interface::CommandInterface>(
153153
traction_joints_names_[0], traction_interface_name_,
154154
&joint_command_values_[CMD_TRACTION_WHEEL]));
155-
command_ifs.emplace_back(command_itfs_.back());
155+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
156156

157157
command_itfs_.emplace_back(
158-
hardware_interface::CommandInterface(
158+
std::make_shared<hardware_interface::CommandInterface>(
159159
steering_joints_names_[0], steering_interface_name_,
160160
&joint_command_values_[CMD_STEER_WHEEL]));
161-
command_ifs.emplace_back(command_itfs_.back());
161+
loaned_command_ifs.emplace_back(command_itfs_.back(), nullptr);
162162

163-
std::vector<hardware_interface::LoanedStateInterface> state_ifs;
163+
std::vector<hardware_interface::LoanedStateInterface> loaned_state_ifs;
164164
state_itfs_.reserve(joint_state_values_.size());
165-
state_ifs.reserve(joint_state_values_.size());
165+
loaned_state_ifs.reserve(joint_state_values_.size());
166166

167167
state_itfs_.emplace_back(
168-
hardware_interface::StateInterface(
168+
std::make_shared<hardware_interface::StateInterface>(
169169
traction_joints_names_[0], traction_interface_name_,
170170
&joint_state_values_[STATE_TRACTION_WHEEL]));
171-
state_ifs.emplace_back(state_itfs_.back());
171+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
172172

173173
state_itfs_.emplace_back(
174-
hardware_interface::StateInterface(
174+
std::make_shared<hardware_interface::StateInterface>(
175175
steering_joints_names_[0], steering_interface_name_,
176176
&joint_state_values_[STATE_STEER_AXIS]));
177-
state_ifs.emplace_back(state_itfs_.back());
177+
loaned_state_ifs.emplace_back(state_itfs_.back(), nullptr);
178178

179-
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));
179+
controller_->assign_interfaces(std::move(loaned_command_ifs), std::move(loaned_state_ifs));
180180
}
181181

182182
void subscribe_and_get_messages(ControllerStateMsg & msg)
@@ -275,8 +275,8 @@ class BicycleSteeringControllerFixture : public ::testing::Test
275275
std::string traction_interface_name_ = "";
276276
std::string preceding_prefix_ = "pid_controller";
277277

278-
std::vector<hardware_interface::StateInterface> state_itfs_;
279-
std::vector<hardware_interface::CommandInterface> command_itfs_;
278+
std::vector<hardware_interface::StateInterface::SharedPtr> state_itfs_;
279+
std::vector<hardware_interface::CommandInterface::SharedPtr> command_itfs_;
280280

281281
// Test related parameters
282282
std::unique_ptr<TestableBicycleSteeringController> controller_;

chained_filter_controller/test/test_chained_filter.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -123,18 +123,18 @@ TEST_F(ChainedFilterTest, UpdateFilter)
123123
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
124124
controller_interface::return_type::OK);
125125
// input state interface should not change
126-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
126+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
127127
// output should be the same
128128
auto state_if_exported_conf = controller_->export_state_interfaces();
129129
ASSERT_THAT(state_if_exported_conf, SizeIs(1u));
130130
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), joint_states_[0]);
131131

132-
ASSERT_TRUE(joint_1_pos_.set_value(2.0));
132+
ASSERT_TRUE(joint_1_pos_->set_value(2.0));
133133
ASSERT_EQ(
134134
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
135135
controller_interface::return_type::OK);
136136
// input and output should have changed
137-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
137+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
138138
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), 1.55);
139139
ASSERT_EQ(
140140
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),

chained_filter_controller/test/test_chained_filter.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,8 @@ class ChainedFilterTest : public ::testing::Test
4949
const std::vector<std::string> joint_names_ = {"wheel_left"};
5050
std::vector<double> joint_states_ = {1.1};
5151

52-
StateInterface joint_1_pos_{joint_names_[0], HW_IF_POSITION, &joint_states_[0]};
52+
StateInterface::SharedPtr joint_1_pos_ =
53+
std::make_shared<StateInterface>(joint_names_[0], HW_IF_POSITION, &joint_states_[0]);
5354
rclcpp::executors::SingleThreadedExecutor executor;
5455
};
5556

chained_filter_controller/test/test_multiple_chained_filter.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,8 @@ void MultipleChainedFilterTest::SetUpController(
5252
ASSERT_EQ(result, controller_interface::return_type::OK);
5353

5454
std::vector<LoanedStateInterface> state_ifs;
55-
state_ifs.emplace_back(joint_1_pos_);
56-
state_ifs.emplace_back(joint_2_pos_);
55+
state_ifs.emplace_back(joint_1_pos_, nullptr);
56+
state_ifs.emplace_back(joint_2_pos_, nullptr);
5757
controller_->assign_interfaces({}, std::move(state_ifs));
5858
executor.add_node(controller_->get_node()->get_node_base_interface());
5959
}
@@ -118,23 +118,23 @@ TEST_F(MultipleChainedFilterTest, UpdateFilter_multiple_interfaces)
118118
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
119119
controller_interface::return_type::OK);
120120
// input state interface should not change
121-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
122-
EXPECT_EQ(joint_2_pos_.get_optional().value(), joint_states_[1]);
121+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
122+
EXPECT_EQ(joint_2_pos_->get_optional().value(), joint_states_[1]);
123123
// output should be the same
124124
auto state_if_exported_conf = controller_->export_state_interfaces();
125125
ASSERT_THAT(state_if_exported_conf, SizeIs(2u));
126126
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), joint_states_[0]);
127127
EXPECT_EQ(state_if_exported_conf[1]->get_optional().value(), joint_states_[1]);
128128

129-
ASSERT_TRUE(joint_1_pos_.set_value(2.0));
130-
ASSERT_TRUE(joint_2_pos_.set_value(3.0));
129+
ASSERT_TRUE(joint_1_pos_->set_value(2.0));
130+
ASSERT_TRUE(joint_2_pos_->set_value(3.0));
131131
ASSERT_EQ(
132132
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
133133
controller_interface::return_type::OK);
134134
// input and output should have changed
135-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
135+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
136136
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), 1.55);
137-
EXPECT_EQ(joint_2_pos_.get_optional().value(), joint_states_[1]);
137+
EXPECT_EQ(joint_2_pos_->get_optional().value(), joint_states_[1]);
138138
EXPECT_EQ(state_if_exported_conf[1]->get_optional().value(), 2.6);
139139

140140
ASSERT_EQ(
@@ -155,23 +155,23 @@ TEST_F(MultipleChainedFilterTest, UpdateFilter_multiple_interfaces_config_per_in
155155
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
156156
controller_interface::return_type::OK);
157157
// input state interface should not change
158-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
159-
EXPECT_EQ(joint_2_pos_.get_optional().value(), joint_states_[1]);
158+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
159+
EXPECT_EQ(joint_2_pos_->get_optional().value(), joint_states_[1]);
160160
// output should be the same
161161
auto state_if_exported_conf = controller_->export_state_interfaces();
162162
ASSERT_THAT(state_if_exported_conf, SizeIs(2u));
163163
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), joint_states_[0]);
164164
EXPECT_EQ(state_if_exported_conf[1]->get_optional().value(), joint_states_[1]);
165165

166-
ASSERT_TRUE(joint_1_pos_.set_value(2.0));
167-
ASSERT_TRUE(joint_2_pos_.set_value(2.8));
166+
ASSERT_TRUE(joint_1_pos_->set_value(2.0));
167+
ASSERT_TRUE(joint_2_pos_->set_value(2.8));
168168
ASSERT_EQ(
169169
controller_->update_and_write_commands(rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)),
170170
controller_interface::return_type::OK);
171171
// input and output should have changed
172-
EXPECT_EQ(joint_1_pos_.get_optional().value(), joint_states_[0]);
172+
EXPECT_EQ(joint_1_pos_->get_optional().value(), joint_states_[0]);
173173
EXPECT_EQ(state_if_exported_conf[0]->get_optional().value(), 1.55);
174-
EXPECT_EQ(joint_2_pos_.get_optional().value(), joint_states_[1]);
174+
EXPECT_EQ(joint_2_pos_->get_optional().value(), joint_states_[1]);
175175
// second update call, mean of (2.2, 2.8)
176176
EXPECT_EQ(state_if_exported_conf[1]->get_optional().value(), 2.5);
177177

chained_filter_controller/test/test_multiple_chained_filter.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,10 @@ class MultipleChainedFilterTest : public ::testing::Test
4949
const std::vector<std::string> joint_names_ = {"wheel_left", "wheel_right"};
5050
std::vector<double> joint_states_ = {1.1, 2.2};
5151

52-
StateInterface joint_1_pos_{joint_names_[0], HW_IF_POSITION, &joint_states_[0]};
53-
StateInterface joint_2_pos_{joint_names_[1], HW_IF_POSITION, &joint_states_[1]};
52+
StateInterface::SharedPtr joint_1_pos_ =
53+
std::make_shared<StateInterface>(joint_names_[0], HW_IF_POSITION, &joint_states_[0]);
54+
StateInterface::SharedPtr joint_2_pos_ =
55+
std::make_shared<StateInterface>(joint_names_[1], HW_IF_POSITION, &joint_states_[1]);
5456
rclcpp::executors::SingleThreadedExecutor executor;
5557
};
5658

0 commit comments

Comments
 (0)