Skip to content

Commit afb605f

Browse files
author
Minggang Wang
committed
Replace the deprecated methods used in the tests written in C++
Fix #515
1 parent 6c8850d commit afb605f

File tree

4 files changed

+95
-104
lines changed

4 files changed

+95
-104
lines changed

test/cpp/add_two_ints_client.cpp

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -82,13 +82,9 @@ int main(int argc, char ** argv)
8282
printf("service not available, waiting again...\n");
8383
}
8484

85-
// TODO(wjwwood): make it like `client->send_request(node, request)->sum`
86-
// TODO(wjwwood): consider error condition
87-
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
88-
custom_qos_profile.depth = 7;
8985
auto msg = std::make_shared<std_msgs::msg::Int8>();
9086
publisher = node->create_publisher<std_msgs::msg::Int8>(
91-
std::string("back_") + topic, custom_qos_profile);
87+
std::string("back_") + topic, 7);
9288

9389

9490
auto future_result = client->async_send_request(request);
@@ -99,7 +95,7 @@ int main(int argc, char ** argv)
9995
{
10096
// printf("Result of add_two_ints: %zd\n", future_result.get()->sum);
10197
msg->data = future_result.get()->sum;
102-
publisher->publish(msg);
98+
publisher->publish(*msg);
10399
} else {
104100
printf("add_two_ints_client_async was interrupted. Exiting.\n");
105101
}

test/cpp/listener.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ void print_usage()
3434

3535
void chatterCallback(const std_msgs::msg::String::SharedPtr msg)
3636
{
37-
publisher->publish(msg);
37+
publisher->publish(*msg);
3838
}
3939

4040

@@ -48,17 +48,15 @@ int main(int argc, char * argv[])
4848
print_usage();
4949
return 0;
5050
}
51-
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
52-
custom_qos_profile.depth = 7;
5351
auto topic = std::string("chatter");
5452
if (rcutils_cli_option_exist(argv, argv + argc, "-t")) {
5553
topic = std::string(rcutils_cli_get_option(argv, argv + argc, "-t"));
5654
}
5755

5856
publisher = node->create_publisher<std_msgs::msg::String>(
59-
std::string("back_") + topic, custom_qos_profile);
57+
std::string("back_") + topic, 7);
6058
auto sub = node->create_subscription<std_msgs::msg::String>(
61-
topic, chatterCallback, rmw_qos_profile_default);
59+
topic, 7, chatterCallback);
6260

6361
rclcpp::spin(node);
6462

test/cpp/publisher_msg.cpp

Lines changed: 36 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -75,9 +75,6 @@ int main(int argc, char* argv[]) {
7575

7676
auto node = rclcpp::Node::make_shared("cpp_publisher");
7777

78-
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
79-
custom_qos_profile.depth = 7;
80-
8178
if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
8279
print_usage();
8380
return 0;
@@ -93,86 +90,86 @@ int main(int argc, char* argv[]) {
9390
}
9491

9592
// Bool
96-
auto bool_publisher = node->create_publisher<std_msgs::msg::Bool>(topic, custom_qos_profile);
93+
auto bool_publisher = node->create_publisher<std_msgs::msg::Bool>(topic, 7);
9794
auto bool_msg = std::make_shared<std_msgs::msg::Bool>();
9895
bool_msg->data = true;
9996

10097
// Byte
101-
auto byte_publisher = node->create_publisher<std_msgs::msg::Byte>(topic, custom_qos_profile);
98+
auto byte_publisher = node->create_publisher<std_msgs::msg::Byte>(topic, 7);
10299
auto byte_msg = std::make_shared<std_msgs::msg::Byte>();
103100
byte_msg->data = 255;
104101

105102
// Char
106-
auto char_publisher = node->create_publisher<std_msgs::msg::Char>(topic, custom_qos_profile);
103+
auto char_publisher = node->create_publisher<std_msgs::msg::Char>(topic, 7);
107104
auto char_msg = std::make_shared<std_msgs::msg::Char>();
108105
char_msg->data = 'A';
109106

110107
// String
111-
auto string_publisher = node->create_publisher<std_msgs::msg::String>(topic, custom_qos_profile);
108+
auto string_publisher = node->create_publisher<std_msgs::msg::String>(topic, 7);
112109
auto string_msg = std::make_shared<std_msgs::msg::String>();
113110
string_msg->data = std::string("Hello World");
114111

115112
// Int8
116-
auto int8_publisher = node->create_publisher<std_msgs::msg::Int8>(topic, custom_qos_profile);
113+
auto int8_publisher = node->create_publisher<std_msgs::msg::Int8>(topic, 7);
117114
auto int8_msg = std::make_shared<std_msgs::msg::Int8>();
118115
int8_msg->data = 127;
119116

120117
// UInt8
121-
auto uint8_publisher = node->create_publisher<std_msgs::msg::UInt8>(topic, custom_qos_profile);
118+
auto uint8_publisher = node->create_publisher<std_msgs::msg::UInt8>(topic, 7);
122119
auto uint8_msg = std::make_shared<std_msgs::msg::UInt8>();
123120
uint8_msg->data = 255;
124121

125122
// Int16
126-
auto int16_publisher = node->create_publisher<std_msgs::msg::Int16>(topic, custom_qos_profile);
123+
auto int16_publisher = node->create_publisher<std_msgs::msg::Int16>(topic, 7);
127124
auto int16_msg = std::make_shared<std_msgs::msg::Int16>();
128125
int16_msg->data = 0x7fff;
129126

130127
// UInt16
131-
auto uint16_publisher = node->create_publisher<std_msgs::msg::UInt16>(topic, custom_qos_profile);
128+
auto uint16_publisher = node->create_publisher<std_msgs::msg::UInt16>(topic, 7);
132129
auto uint16_msg = std::make_shared<std_msgs::msg::UInt16>();
133130
uint16_msg->data = 0xffff;
134131

135132
// Int32
136-
auto int32_publisher = node->create_publisher<std_msgs::msg::Int32>(topic, custom_qos_profile);
133+
auto int32_publisher = node->create_publisher<std_msgs::msg::Int32>(topic, 7);
137134
auto int32_msg = std::make_shared<std_msgs::msg::Int32>();
138135
int32_msg->data = 0x7fffffffL;
139136

140137
// UInt32
141-
auto uint32_publisher = node->create_publisher<std_msgs::msg::UInt32>(topic, custom_qos_profile);
138+
auto uint32_publisher = node->create_publisher<std_msgs::msg::UInt32>(topic, 7);
142139
auto uint32_msg = std::make_shared<std_msgs::msg::UInt32>();
143140
uint32_msg->data = 0xffffffffUL;
144141

145142
// Int64
146-
auto int64_publisher = node->create_publisher<std_msgs::msg::Int64>(topic, custom_qos_profile);
143+
auto int64_publisher = node->create_publisher<std_msgs::msg::Int64>(topic, 7);
147144
auto int64_msg = std::make_shared<std_msgs::msg::Int64>();
148145
long long max_js_int = (2LL << 52) - 1;
149146
int64_msg->data = max_js_int;
150147

151148
// UInt64
152-
auto uint64_publisher = node->create_publisher<std_msgs::msg::UInt64>(topic, custom_qos_profile);
149+
auto uint64_publisher = node->create_publisher<std_msgs::msg::UInt64>(topic, 7);
153150
auto uint64_msg = std::make_shared<std_msgs::msg::UInt64>();
154151
uint64_msg->data = max_js_int;
155152

156153
// Float32
157-
auto float32_publisher = node->create_publisher<std_msgs::msg::Float32>(topic, custom_qos_profile);
154+
auto float32_publisher = node->create_publisher<std_msgs::msg::Float32>(topic, 7);
158155
auto float32_msg = std::make_shared<std_msgs::msg::Float32>();
159156
float32_msg->data = 3.14;
160157

161158
// Float64
162-
auto float64_publisher = node->create_publisher<std_msgs::msg::Float64>(topic, custom_qos_profile);
159+
auto float64_publisher = node->create_publisher<std_msgs::msg::Float64>(topic, 7);
163160
auto float64_msg = std::make_shared<std_msgs::msg::Float64>();
164161
float64_msg->data = 3.1415926;
165162

166163
// ColorRGBA
167-
auto colorrgba_publisher = node->create_publisher<std_msgs::msg::ColorRGBA>(topic, custom_qos_profile);
164+
auto colorrgba_publisher = node->create_publisher<std_msgs::msg::ColorRGBA>(topic, 7);
168165
auto colorrgba_msg = std::make_shared<std_msgs::msg::ColorRGBA>();
169166
colorrgba_msg->a = 0.5;
170167
colorrgba_msg->r = 127;
171168
colorrgba_msg->g = 255;
172169
colorrgba_msg->b = 255;
173170

174171
// Array
175-
auto array_publisher = node->create_publisher<std_msgs::msg::ByteMultiArray>(topic, custom_qos_profile);
172+
auto array_publisher = node->create_publisher<std_msgs::msg::ByteMultiArray>(topic, 7);
176173
auto dim = std::make_shared<std_msgs::msg::MultiArrayDimension>();
177174
dim->label = std::string("length");
178175
dim->size = 1;
@@ -187,7 +184,7 @@ int main(int argc, char* argv[]) {
187184
array_msg->data = std::vector<uint8_t>{65, 66, 67};
188185

189186
// Header
190-
auto header_publisher = node->create_publisher<std_msgs::msg::Header>(topic, custom_qos_profile);
187+
auto header_publisher = node->create_publisher<std_msgs::msg::Header>(topic, 7);
191188
auto time = std::make_shared<builtin_interfaces::msg::Time>();
192189
time->sec = 123456;
193190
time->nanosec = 789;
@@ -197,7 +194,7 @@ int main(int argc, char* argv[]) {
197194
header_msg->frame_id = std::string("main frame");
198195

199196
// Complex object: JointState
200-
auto jointstate_publisher = node->create_publisher<sensor_msgs::msg::JointState>(topic, custom_qos_profile);
197+
auto jointstate_publisher = node->create_publisher<sensor_msgs::msg::JointState>(topic, 7);
201198
auto head_time = std::make_shared<builtin_interfaces::msg::Time>();
202199
head_time->sec = 123456;
203200
head_time->nanosec = 789;
@@ -218,58 +215,58 @@ int main(int argc, char* argv[]) {
218215
// std::cout << "Publishing: '" << msg->data << "'" << std::endl;
219216
switch (msg_type_map[msg_type]) {
220217
case 1:
221-
bool_publisher->publish(bool_msg);
218+
bool_publisher->publish(*bool_msg);
222219
break;
223220
case 2:
224-
byte_publisher->publish(byte_msg);
221+
byte_publisher->publish(*byte_msg);
225222
break;
226223
case 3:
227-
char_publisher->publish(char_msg);
224+
char_publisher->publish(*char_msg);
228225
break;
229226
case 4:
230-
string_publisher->publish(string_msg);
227+
string_publisher->publish(*string_msg);
231228
break;
232229
case 5:
233-
int8_publisher->publish(int8_msg);
230+
int8_publisher->publish(*int8_msg);
234231
break;
235232
case 6:
236-
uint8_publisher->publish(uint8_msg);
233+
uint8_publisher->publish(*uint8_msg);
237234
break;
238235
case 7:
239-
int16_publisher->publish(int16_msg);
236+
int16_publisher->publish(*int16_msg);
240237
break;
241238
case 8:
242-
uint16_publisher->publish(uint16_msg);
239+
uint16_publisher->publish(*uint16_msg);
243240
break;
244241
case 9:
245-
int32_publisher->publish(int32_msg);
242+
int32_publisher->publish(*int32_msg);
246243
break;
247244
case 10:
248-
uint32_publisher->publish(uint32_msg);
245+
uint32_publisher->publish(*uint32_msg);
249246
break;
250247
case 11:
251-
int64_publisher->publish(int64_msg);
248+
int64_publisher->publish(*int64_msg);
252249
break;
253250
case 12:
254-
uint64_publisher->publish(uint64_msg);
251+
uint64_publisher->publish(*uint64_msg);
255252
break;
256253
case 13:
257-
float32_publisher->publish(float32_msg);
254+
float32_publisher->publish(*float32_msg);
258255
break;
259256
case 14:
260-
float64_publisher->publish(float64_msg);
257+
float64_publisher->publish(*float64_msg);
261258
break;
262259
case 15:
263-
colorrgba_publisher->publish(colorrgba_msg);
260+
colorrgba_publisher->publish(*colorrgba_msg);
264261
break;
265262
case 16:
266-
array_publisher->publish(array_msg);
263+
array_publisher->publish(*array_msg);
267264
break;
268265
case 17:
269-
header_publisher->publish(header_msg);
266+
header_publisher->publish(*header_msg);
270267
break;
271268
case 18:
272-
jointstate_publisher->publish(jointstate_msg);
269+
jointstate_publisher->publish(*jointstate_msg);
273270
break;
274271
default:
275272
std::cerr << "Unsupported message types" << std::endl;

0 commit comments

Comments
 (0)