Skip to content

Commit ad27118

Browse files
Fix "parameter is already declared" error
1 parent df051d3 commit ad27118

File tree

1 file changed

+30
-37
lines changed

1 file changed

+30
-37
lines changed

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp

+30-37
Original file line numberDiff line numberDiff line change
@@ -111,12 +111,11 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_InterfaceNames_Set)
111111
SetUpFTSBroadcaster();
112112

113113
// set the 'sensor_name'
114-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", sensor_name_);
114+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
115115

116116
// set the 'interface_names'
117-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "fts_sensor/force.x");
118-
fts_broadcaster_->get_node()->declare_parameter(
119-
"interface_names.torque.z", "fts_sensor/torque.z");
117+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
118+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});
120119

121120
// configure failed, both 'sensor_name' and 'interface_names' supplied
122121
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);
@@ -127,7 +126,7 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_IsEmpty_InterfaceNames_NotSe
127126
SetUpFTSBroadcaster();
128127

129128
// set the 'sensor_name' empty
130-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", "");
129+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", ""});
131130

132131
// configure failed, 'sensor_name' parameter empty
133132
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);
@@ -138,8 +137,8 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_IsEmpty_SensorName_NotSe
138137
SetUpFTSBroadcaster();
139138

140139
// set the 'interface_names' empty
141-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "");
142-
fts_broadcaster_->get_node()->declare_parameter("interface_names.torque.z", "");
140+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", ""});
141+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", ""});
143142

144143
// configure failed, 'interface_name' parameter empty
145144
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);
@@ -150,10 +149,10 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Configure_Success)
150149
SetUpFTSBroadcaster();
151150

152151
// set the 'sensor_name'
153-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", sensor_name_);
152+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
154153

155154
// set the 'frame_id'
156-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
155+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
157156

158157
// configure passed
159158
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -164,12 +163,11 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
164163
SetUpFTSBroadcaster();
165164

166165
// set the 'interface_names'
167-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "fts_sensor/force.x");
168-
fts_broadcaster_->get_node()->declare_parameter(
169-
"interface_names.torque.z", "fts_sensor/torque.z");
166+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
167+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});
170168

171169
// set the 'frame_id'
172-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
170+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
173171

174172
// configure passed
175173
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -180,8 +178,8 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Activate_Success)
180178
SetUpFTSBroadcaster();
181179

182180
// set the params 'sensor_name' and 'frame_id'
183-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", sensor_name_);
184-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
181+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
182+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
185183

186184
// configure and activate success
187185
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -193,8 +191,8 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Update_Success)
193191
SetUpFTSBroadcaster();
194192

195193
// set the params 'sensor_name' and 'frame_id'
196-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", sensor_name_);
197-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
194+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
195+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
198196

199197
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
200198
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -209,10 +207,9 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Success)
209207
SetUpFTSBroadcaster();
210208

211209
// set the params 'interface_names' and 'frame_id'
212-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "fts_sensor/force.x");
213-
fts_broadcaster_->get_node()->declare_parameter(
214-
"interface_names.torque.z", "fts_sensor/torque.z");
215-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
210+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
211+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});
212+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
216213

217214
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
218215
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -226,8 +223,8 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Publish_Success)
226223
SetUpFTSBroadcaster();
227224

228225
// set the params 'sensor_name' and 'frame_id'
229-
fts_broadcaster_->get_node()->declare_parameter("sensor_name", sensor_name_);
230-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
226+
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
227+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
231228

232229
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
233230
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -249,10 +246,9 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Publish_Success)
249246
SetUpFTSBroadcaster();
250247

251248
// set the params 'interface_names' and 'frame_id'
252-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "fts_sensor/force.x");
253-
fts_broadcaster_->get_node()->declare_parameter(
254-
"interface_names.torque.z", "fts_sensor/torque.z");
255-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
249+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
250+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});
251+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
256252

257253
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
258254
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
@@ -274,16 +270,13 @@ TEST_F(ForceTorqueSensorBroadcasterTest, All_InterfaceNames_Publish_Success)
274270
SetUpFTSBroadcaster();
275271

276272
// set all the params 'interface_names' and 'frame_id'
277-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.x", "fts_sensor/force.x");
278-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.y", "fts_sensor/force.y");
279-
fts_broadcaster_->get_node()->declare_parameter("interface_names.force.z", "fts_sensor/force.z");
280-
fts_broadcaster_->get_node()->declare_parameter(
281-
"interface_names.torque.x", "fts_sensor/torque.x");
282-
fts_broadcaster_->get_node()->declare_parameter(
283-
"interface_names.torque.y", "fts_sensor/torque.y");
284-
fts_broadcaster_->get_node()->declare_parameter(
285-
"interface_names.torque.z", "fts_sensor/torque.z");
286-
fts_broadcaster_->get_node()->declare_parameter("frame_id", frame_id_);
273+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
274+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.y", "fts_sensor/force.y"});
275+
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.z", "fts_sensor/force.z"});
276+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.x", "fts_sensor/torque.x"});
277+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.y", "fts_sensor/torque.y"});
278+
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});
279+
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
287280

288281
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
289282
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);

0 commit comments

Comments
 (0)