-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy paththroughput_publisher.cc
80 lines (62 loc) · 1.75 KB
/
throughput_publisher.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
#include <getopt.h>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/byte_multi_array.hpp>
namespace {
struct Options
{
size_t payloadSize{1};
};
void showHelp(const std::string &name)
{
std::cout << "usage: " << name << " OPTIONS\n"
"OPTIONS:\n"
" -p | --payload-size payload size in bytes; valid bounds [1, 1e9].\n"
" -h | --help show this help.\n";
}
Options parseOpts(int argc, char **argv)
{
static constexpr auto shortOpts = "p:h";
static constexpr struct option longOpts[] = {
{ "payload-size", required_argument, nullptr, 'p' },
{ "help", no_argument, nullptr, 'h' },
{ nullptr, 0, nullptr, 0 }
};
Options opts{ };
for (int c = 0; (c = getopt_long(argc, argv, shortOpts, longOpts, nullptr)) >= 0; )
{
switch (c)
{
case 'p':
opts.payloadSize = std::clamp<size_t>(std::stod(optarg), 1, 1e9);
break;
case 'h':
showHelp(argv[0]);
std::exit(0);
case '?':
std::exit(1);
default:
break;
}
}
if (optind < argc)
{
std::cerr << argv[0] << ": trailing args..\n";
std::exit(1);
}
return opts;
}
}
int main(int argc, char **argv)
{
rclcpp::init(argc, argv, rclcpp::InitOptions());
auto opts = parseOpts(argc, argv);
auto node = std::make_shared<rclcpp::Node>("throughput_publisher");
auto payloadPub = node->create_publisher<std_msgs::msg::ByteMultiArray>("payload", 1);
auto payload = std_msgs::msg::ByteMultiArray{ };
payload.data.resize(opts.payloadSize);
while (rclcpp::ok())
{
payloadPub->publish(payload);
}
return 0;
}