ros1_foxglove_bridge/tests/smoke_test.cpp
Go to the documentation of this file.
1 #include <chrono>
2 #include <future>
3 #include <thread>
4 
5 #include <boost/filesystem.hpp>
6 #include <gtest/gtest.h>
7 #include <ros/ros.h>
9 #include <std_srvs/SetBool.h>
10 #include <websocketpp/config/asio_client.hpp>
11 
14 
15 constexpr char URI[] = "ws://localhost:9876";
16 
17 // Binary representation of std_msgs/String for "hello world"
18 constexpr uint8_t HELLO_WORLD_BINARY[] = {11, 0, 0, 0, 104, 101, 108, 108,
19  111, 32, 119, 111, 114, 108, 100};
20 
21 constexpr auto ONE_SECOND = std::chrono::seconds(1);
22 constexpr auto DEFAULT_TIMEOUT = std::chrono::seconds(8);
23 
24 class ParameterTest : public ::testing::Test {
25 public:
26  using PARAM_1_TYPE = std::string;
27  inline static const std::string PARAM_1_NAME = "/node_1/string_param";
28  inline static const PARAM_1_TYPE PARAM_1_DEFAULT_VALUE = "hello";
29 
30  using PARAM_2_TYPE = std::vector<double>;
31  inline static const std::string PARAM_2_NAME = "/node_2/int_array_param";
32  inline static const PARAM_2_TYPE PARAM_2_DEFAULT_VALUE = {1.2, 2.1, 3.3};
33 
34 protected:
35  void SetUp() override {
36  _nh = ros::NodeHandle();
39 
40  _wsClient = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
41  ASSERT_EQ(std::future_status::ready, _wsClient->connect(URI).wait_for(DEFAULT_TIMEOUT));
42  }
43 
45  std::shared_ptr<foxglove::Client<websocketpp::config::asio_client>> _wsClient;
46 };
47 
48 class ServiceTest : public ::testing::Test {
49 public:
50  inline static const std::string SERVICE_NAME = "/foo_service";
51 
52 protected:
53  void SetUp() override {
54  _nh = ros::NodeHandle();
55  _service = _nh.advertiseService<std_srvs::SetBool::Request, std_srvs::SetBool::Response>(
56  SERVICE_NAME, [&](auto& req, auto& res) {
57  res.message = "hello";
58  res.success = req.data;
59  return true;
60  });
61  }
62 
63 private:
66 };
67 
68 TEST(SmokeTest, testConnection) {
70  EXPECT_EQ(std::future_status::ready, wsClient.connect(URI).wait_for(DEFAULT_TIMEOUT));
71 }
72 
73 TEST(SmokeTest, testSubscription) {
74  // Publish a string message on a latched ros topic
75  const std::string topic_name = "/pub_topic";
76  ros::NodeHandle nh;
77  auto pub = nh.advertise<std_msgs::String>(topic_name, 10, true);
78  pub.publish(std::string("hello world"));
79 
80  // Connect a few clients and make sure that they receive the correct message
81  const auto clientCount = 3;
82  for (auto i = 0; i < clientCount; ++i) {
83  // Set up a client and subscribe to the channel.
84  auto client = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
85  auto channelFuture = foxglove::waitForChannel(client, topic_name);
86  ASSERT_EQ(std::future_status::ready, client->connect(URI).wait_for(ONE_SECOND));
87  ASSERT_EQ(std::future_status::ready, channelFuture.wait_for(DEFAULT_TIMEOUT));
88  const foxglove::Channel channel = channelFuture.get();
89  const foxglove::SubscriptionId subscriptionId = 1;
90 
91  // Subscribe to the channel and confirm that the promise resolves
92  auto msgFuture = waitForChannelMsg(client.get(), subscriptionId);
93  client->subscribe({{subscriptionId, channel.id}});
94  ASSERT_EQ(std::future_status::ready, msgFuture.wait_for(ONE_SECOND));
95  const auto msgData = msgFuture.get();
96  ASSERT_EQ(sizeof(HELLO_WORLD_BINARY), msgData.size());
97  EXPECT_EQ(0, std::memcmp(HELLO_WORLD_BINARY, msgData.data(), msgData.size()));
98 
99  // Unsubscribe from the channel again.
100  client->unsubscribe({subscriptionId});
101  }
102 }
103 
104 TEST(SmokeTest, testSubscriptionParallel) {
105  // Publish a string message on a latched ros topic
106  const std::string topic_name = "/pub_topic";
107  ros::NodeHandle nh;
108  auto pub = nh.advertise<std_msgs::String>(topic_name, 10, true);
109  pub.publish(std::string("hello world"));
110 
111  // Connect a few clients (in parallel) and make sure that they receive the correct message
112  const foxglove::SubscriptionId subscriptionId = 1;
113  auto clients = {
114  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
116  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
117  };
118 
119  std::vector<std::future<std::vector<uint8_t>>> futures;
120  for (auto client : clients) {
121  futures.push_back(waitForChannelMsg(client.get(), subscriptionId));
122  }
123 
124  for (auto client : clients) {
125  auto channelFuture = foxglove::waitForChannel(client, topic_name);
126  ASSERT_EQ(std::future_status::ready, client->connect(URI).wait_for(ONE_SECOND));
127  ASSERT_EQ(std::future_status::ready, channelFuture.wait_for(DEFAULT_TIMEOUT));
128  const foxglove::Channel channel = channelFuture.get();
129  client->subscribe({{subscriptionId, channel.id}});
130  }
131 
132  for (auto& future : futures) {
133  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
134  auto msgData = future.get();
135  ASSERT_EQ(sizeof(HELLO_WORLD_BINARY), msgData.size());
136  EXPECT_EQ(0, std::memcmp(HELLO_WORLD_BINARY, msgData.data(), msgData.size()));
137  }
138 
139  for (auto client : clients) {
140  client->unsubscribe({subscriptionId});
141  }
142 }
143 
144 TEST(SmokeTest, testPublishing) {
146 
147  foxglove::ClientAdvertisement advertisement;
148  advertisement.channelId = 1;
149  advertisement.topic = "/foo";
150  advertisement.encoding = "ros1";
151  advertisement.schemaName = "std_msgs/String";
152 
153  // Set up a ROS node with a subscriber
154  ros::NodeHandle nh;
155  std::promise<std::string> msgPromise;
156  auto msgFuture = msgPromise.get_future();
157  auto subscriber = nh.subscribe<std_msgs::String>(
158  advertisement.topic, 10, [&msgPromise](const std_msgs::String::ConstPtr& msg) {
159  msgPromise.set_value(msg->data);
160  });
161 
162  // Set up the client, advertise and publish the binary message
163  ASSERT_EQ(std::future_status::ready, wsClient.connect(URI).wait_for(DEFAULT_TIMEOUT));
164  wsClient.advertise({advertisement});
165  std::this_thread::sleep_for(ONE_SECOND);
166  wsClient.publish(advertisement.channelId, HELLO_WORLD_BINARY, sizeof(HELLO_WORLD_BINARY));
167  wsClient.unadvertise({advertisement.channelId});
168 
169  // Ensure that we have received the correct message via our ROS subscriber
170  const auto msgResult = msgFuture.wait_for(ONE_SECOND);
171  ASSERT_EQ(std::future_status::ready, msgResult);
172  EXPECT_EQ("hello world", msgFuture.get());
173 }
174 
175 TEST_F(ParameterTest, testGetAllParams) {
176  const std::string requestId = "req-testGetAllParams";
177  auto future = foxglove::waitForParameters(_wsClient, requestId);
178  _wsClient->getParameters({}, requestId);
179  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
180  std::vector<foxglove::Parameter> params = future.get();
181 
182  EXPECT_GE(params.size(), 2UL);
183 }
184 
185 TEST_F(ParameterTest, testGetNonExistingParameters) {
186  const std::string requestId = "req-testGetNonExistingParameters";
187  auto future = foxglove::waitForParameters(_wsClient, requestId);
188  _wsClient->getParameters(
189  {"/foo_1/non_existing_parameter", "/foo_2/non_existing/nested_parameter"}, requestId);
190  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
191  std::vector<foxglove::Parameter> params = future.get();
192 
193  EXPECT_TRUE(params.empty());
194 }
195 
196 TEST_F(ParameterTest, testGetParameters) {
197  const std::string requestId = "req-testGetParameters";
198  auto future = foxglove::waitForParameters(_wsClient, requestId);
199  _wsClient->getParameters({PARAM_1_NAME, PARAM_2_NAME}, requestId);
200  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
201  std::vector<foxglove::Parameter> params = future.get();
202 
203  EXPECT_EQ(2UL, params.size());
204  auto p1Iter = std::find_if(params.begin(), params.end(), [](const auto& param) {
205  return param.getName() == PARAM_1_NAME;
206  });
207  auto p2Iter = std::find_if(params.begin(), params.end(), [](const auto& param) {
208  return param.getName() == PARAM_2_NAME;
209  });
210  ASSERT_NE(p1Iter, params.end());
211  EXPECT_EQ(PARAM_1_DEFAULT_VALUE, p1Iter->getValue().getValue<PARAM_1_TYPE>());
212  ASSERT_NE(p2Iter, params.end());
213 
214  std::vector<double> double_array_val;
215  const auto array_params = p2Iter->getValue().getValue<std::vector<foxglove::ParameterValue>>();
216  for (const auto& paramValue : array_params) {
217  double_array_val.push_back(paramValue.getValue<double>());
218  }
219  EXPECT_EQ(double_array_val, PARAM_2_DEFAULT_VALUE);
220 }
221 
222 TEST_F(ParameterTest, testSetParameters) {
223  const PARAM_1_TYPE newP1value = "world";
224  const std::vector<foxglove::ParameterValue> newP2value = {4.1, 5.5, 6.6};
225 
226  const std::vector<foxglove::Parameter> parameters = {
227  foxglove::Parameter(PARAM_1_NAME, newP1value),
228  foxglove::Parameter(PARAM_2_NAME, newP2value),
229  };
230 
231  _wsClient->setParameters(parameters);
232  const std::string requestId = "req-testSetParameters";
233  auto future = foxglove::waitForParameters(_wsClient, requestId);
234  _wsClient->getParameters({PARAM_1_NAME, PARAM_2_NAME}, requestId);
235  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
236  std::vector<foxglove::Parameter> params = future.get();
237 
238  EXPECT_EQ(2UL, params.size());
239  auto p1Iter = std::find_if(params.begin(), params.end(), [](const auto& param) {
240  return param.getName() == PARAM_1_NAME;
241  });
242  auto p2Iter = std::find_if(params.begin(), params.end(), [](const auto& param) {
243  return param.getName() == PARAM_2_NAME;
244  });
245  ASSERT_NE(p1Iter, params.end());
246  EXPECT_EQ(newP1value, p1Iter->getValue().getValue<PARAM_1_TYPE>());
247  ASSERT_NE(p2Iter, params.end());
248 
249  std::vector<double> double_array_val;
250  const auto array_params = p2Iter->getValue().getValue<std::vector<foxglove::ParameterValue>>();
251  for (const auto& paramValue : array_params) {
252  double_array_val.push_back(paramValue.getValue<double>());
253  }
254  const std::vector<double> expected_value = {4.1, 5.5, 6.6};
255  EXPECT_EQ(double_array_val, expected_value);
256 }
257 
258 TEST_F(ParameterTest, testSetParametersWithReqId) {
259  const PARAM_1_TYPE newP1value = "world";
260  const std::vector<foxglove::Parameter> parameters = {
261  foxglove::Parameter(PARAM_1_NAME, newP1value),
262  };
263 
264  const std::string requestId = "req-testSetParameters";
265  auto future = foxglove::waitForParameters(_wsClient, requestId);
266  _wsClient->setParameters(parameters, requestId);
267  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
268  std::vector<foxglove::Parameter> params = future.get();
269 
270  EXPECT_EQ(1UL, params.size());
271 }
272 
273 TEST_F(ParameterTest, testUnsetParameter) {
274  const std::vector<foxglove::Parameter> parameters = {
275  foxglove::Parameter(PARAM_1_NAME),
276  };
277 
278  const std::string requestId = "req-testUnsetParameter";
279  auto future = foxglove::waitForParameters(_wsClient, requestId);
280  _wsClient->setParameters(parameters, requestId);
281  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
282  std::vector<foxglove::Parameter> params = future.get();
283 
284  EXPECT_EQ(0UL, params.size());
285 }
286 
287 TEST_F(ParameterTest, testParameterSubscription) {
288  auto future = foxglove::waitForParameters(_wsClient);
289 
290  _wsClient->subscribeParameterUpdates({PARAM_1_NAME});
291  _wsClient->setParameters({foxglove::Parameter(PARAM_1_NAME, "foo")});
292  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
293  std::vector<foxglove::Parameter> params = future.get();
294 
295  ASSERT_EQ(1UL, params.size());
296  EXPECT_EQ(params.front().getName(), PARAM_1_NAME);
297 
298  _wsClient->unsubscribeParameterUpdates({PARAM_1_NAME});
299  _wsClient->setParameters({foxglove::Parameter(PARAM_1_NAME, "bar")});
300 
301  future = foxglove::waitForParameters(_wsClient);
302  ASSERT_EQ(std::future_status::timeout, future.wait_for(ONE_SECOND));
303 }
304 
305 TEST_F(ParameterTest, testGetParametersParallel) {
306  // Connect a few clients (in parallel) and make sure that they all receive parameters
307  auto clients = {
308  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
310  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
311  };
312 
313  std::vector<std::future<std::vector<foxglove::Parameter>>> futures;
314  for (auto client : clients) {
315  futures.push_back(
316  std::async(std::launch::async, [client]() -> std::vector<foxglove::Parameter> {
317  if (std::future_status::ready == client->connect(URI).wait_for(DEFAULT_TIMEOUT)) {
318  const std::string requestId = "req-123";
319  auto future = foxglove::waitForParameters(client, requestId);
320  client->getParameters({}, requestId);
321  future.wait_for(DEFAULT_TIMEOUT);
322  if (future.valid()) {
323  return future.get();
324  }
325  }
326  return {};
327  }));
328  }
329 
330  for (auto& future : futures) {
331  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
332  std::vector<foxglove::Parameter> parameters;
333  EXPECT_NO_THROW(parameters = future.get());
334  EXPECT_GE(parameters.size(), 2UL);
335  }
336 }
337 
338 TEST_F(ServiceTest, testCallServiceParallel) {
339  // Connect a few clients (in parallel) and make sure that they can all call the service
340  auto clients = {
341  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
343  std::make_shared<foxglove::Client<websocketpp::config::asio_client>>(),
344  };
345 
346  auto serviceFuture = foxglove::waitForService(*clients.begin(), SERVICE_NAME);
347  for (auto client : clients) {
348  ASSERT_EQ(std::future_status::ready, client->connect(URI).wait_for(std::chrono::seconds(5)));
349  }
350  ASSERT_EQ(std::future_status::ready, serviceFuture.wait_for(std::chrono::seconds(5)));
351  const foxglove::Service service = serviceFuture.get();
352 
353  foxglove::ServiceRequest request;
354  request.serviceId = service.id;
355  request.callId = 123lu;
356  request.encoding = "ros1";
357  request.data = {1}; // Serialized boolean "True"
358 
359  const std::vector<uint8_t> expectedSerializedResponse = {1, 5, 0, 0, 0, 104, 101, 108, 108, 111};
360 
361  std::vector<std::future<foxglove::ServiceResponse>> futures;
362  for (auto client : clients) {
363  futures.push_back(foxglove::waitForServiceResponse(client));
364  client->sendServiceRequest(request);
365  }
366 
367  for (auto& future : futures) {
368  ASSERT_EQ(std::future_status::ready, future.wait_for(std::chrono::seconds(5)));
370  EXPECT_NO_THROW(response = future.get());
371  EXPECT_EQ(response.serviceId, request.serviceId);
372  EXPECT_EQ(response.callId, request.callId);
373  EXPECT_EQ(response.encoding, request.encoding);
374  EXPECT_EQ(response.data, expectedSerializedResponse);
375  }
376 }
377 
378 TEST(FetchAssetTest, fetchExistingAsset) {
379  auto wsClient = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
380  EXPECT_EQ(std::future_status::ready, wsClient->connect(URI).wait_for(DEFAULT_TIMEOUT));
381 
382  const auto millisSinceEpoch = std::chrono::duration_cast<std::chrono::milliseconds>(
383  std::chrono::system_clock::now().time_since_epoch());
384  const auto tmpFilePath =
385  boost::filesystem::temp_directory_path() / std::to_string(millisSinceEpoch.count());
386  constexpr char content[] = "Hello, world";
387  FILE* tmpAssetFile = std::fopen(tmpFilePath.c_str(), "w");
388  std::fputs(content, tmpAssetFile);
389  std::fclose(tmpAssetFile);
390 
391  const std::string uri = std::string("file://") + tmpFilePath.string();
392  const uint32_t requestId = 123;
393 
394  auto future = foxglove::waitForFetchAssetResponse(wsClient);
395  wsClient->fetchAsset(uri, requestId);
396  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
397  const foxglove::FetchAssetResponse response = future.get();
398 
399  EXPECT_EQ(response.requestId, requestId);
401  // +1 since NULL terminator is not written to file.
402  ASSERT_EQ(response.data.size() + 1ul, sizeof(content));
403  EXPECT_EQ(0, std::memcmp(content, response.data.data(), response.data.size()));
404  std::remove(tmpFilePath.c_str());
405 }
406 
407 TEST(FetchAssetTest, fetchNonExistingAsset) {
408  auto wsClient = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
409  EXPECT_EQ(std::future_status::ready, wsClient->connect(URI).wait_for(DEFAULT_TIMEOUT));
410 
411  const std::string assetId = "file:///foo/bar";
412  const uint32_t requestId = 456;
413 
414  auto future = foxglove::waitForFetchAssetResponse(wsClient);
415  wsClient->fetchAsset(assetId, requestId);
416  ASSERT_EQ(std::future_status::ready, future.wait_for(DEFAULT_TIMEOUT));
417  const foxglove::FetchAssetResponse response = future.get();
418 
419  EXPECT_EQ(response.requestId, requestId);
420  EXPECT_EQ(response.status, foxglove::FetchAssetStatus::Error);
421  EXPECT_FALSE(response.errorMessage.empty());
422 }
423 
424 // Run all the tests that were declared with TEST()
425 int main(int argc, char** argv) {
426  testing::InitGoogleTest(&argc, argv);
427  ros::init(argc, argv, "tester");
428  ros::NodeHandle nh;
429 
430  // Give the server some time to start
431  std::this_thread::sleep_for(std::chrono::seconds(2));
432 
433  ros::AsyncSpinner spinner(1);
434  spinner.start();
435  const auto testResult = RUN_ALL_TESTS();
436  spinner.stop();
437 
438  return testResult;
439 }
response
const std::string response
ServiceTest::SERVICE_NAME
static const std::string SERVICE_NAME
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:50
foxglove::Client::advertise
void advertise(const std::vector< ClientAdvertisement > &channels) override
Definition: websocket_client.hpp:169
foxglove::Client
Definition: websocket_client.hpp:60
ParameterTest::PARAM_2_TYPE
std::vector< double > PARAM_2_TYPE
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:30
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
ParameterTest
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:24
ParameterTest::PARAM_1_DEFAULT_VALUE
static const PARAM_1_TYPE PARAM_1_DEFAULT_VALUE
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:28
foxglove::Service::id
ServiceId id
Definition: common.hpp:122
ParameterTest::PARAM_1_TYPE
std::string PARAM_1_TYPE
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:26
foxglove::ClientAdvertisement::topic
std::string topic
Definition: common.hpp:79
foxglove::Channel
Definition: common.hpp:64
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
foxglove::ServiceResponse::encoding
std::string encoding
Definition: common.hpp:133
TEST_F
TEST_F(ParameterTest, testGetAllParams)
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:175
ros.h
ParameterTest::PARAM_1_NAME
static const std::string PARAM_1_NAME
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:27
foxglove::ServiceResponse
Definition: common.hpp:130
ros::AsyncSpinner
foxglove::ServiceResponse::callId
uint32_t callId
Definition: common.hpp:132
foxglove::FetchAssetResponse
Definition: common.hpp:155
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
foxglove::Channel::id
ChannelId id
Definition: common.hpp:65
foxglove::waitForServiceResponse
std::future< ServiceResponse > waitForServiceResponse(std::shared_ptr< ClientInterface > client)
Definition: test_client.cpp:51
foxglove::Client::unadvertise
void unadvertise(const std::vector< ClientChannelId > &channelIds) override
Definition: websocket_client.hpp:174
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
foxglove::ServiceResponse::data
std::vector< uint8_t > data
Definition: common.hpp:134
foxglove::waitForChannelMsg
std::future< std::vector< uint8_t > > waitForChannelMsg(ClientInterface *client, SubscriptionId subscriptionId)
Definition: test_client.cpp:11
ServiceTest::SetUp
void SetUp() override
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:53
ros::ServiceServer
DEFAULT_TIMEOUT
constexpr auto DEFAULT_TIMEOUT
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:22
ParameterTest::PARAM_2_NAME
static const std::string PARAM_2_NAME
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:31
foxglove::ClientAdvertisement::channelId
ClientChannelId channelId
Definition: common.hpp:78
ParameterTest::_nh
ros::NodeHandle _nh
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:44
foxglove::Parameter
Definition: parameter.hpp:54
URI
constexpr char URI[]
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:15
foxglove::waitForService
std::future< Service > waitForService(std::shared_ptr< ClientInterface > client, const std::string &serviceName)
Definition: test_client.cpp:68
foxglove::ClientAdvertisement
Definition: common.hpp:77
foxglove::ServiceResponse::serviceId
ServiceId serviceId
Definition: common.hpp:131
foxglove::waitForFetchAssetResponse
std::future< FetchAssetResponse > waitForFetchAssetResponse(std::shared_ptr< ClientInterface > client)
Definition: test_client.cpp:115
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
foxglove::SubscriptionId
uint32_t SubscriptionId
Definition: common.hpp:28
ParameterTest::SetUp
void SetUp() override
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:35
foxglove::waitForParameters
std::future< std::vector< Parameter > > waitForParameters(std::shared_ptr< ClientInterface > client, const std::string &requestId=std::string())
Definition: test_client.cpp:31
ServiceTest
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:48
ros::AsyncSpinner::stop
void stop()
TEST
TEST(SmokeTest, testConnection)
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:68
foxglove::ClientAdvertisement::encoding
std::string encoding
Definition: common.hpp:80
foxglove::waitForChannel
std::future< Channel > waitForChannel(std::shared_ptr< ClientInterface > client, const std::string &topicName)
Definition: test_client.cpp:92
foxglove::ClientAdvertisement::schemaName
std::string schemaName
Definition: common.hpp:81
main
int main(int argc, char **argv)
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:425
foxglove::Client::connect
void connect(const std::string &uri, std::function< void(websocketpp::connection_hdl)> onOpenHandler, std::function< void(websocketpp::connection_hdl)> onCloseHandler=nullptr) override
Definition: websocket_client.hpp:85
ONE_SECOND
constexpr auto ONE_SECOND
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:21
ServiceTest::_nh
ros::NodeHandle _nh
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:64
ParameterTest::_wsClient
std::shared_ptr< foxglove::Client< websocketpp::config::asio_client > > _wsClient
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:45
ServiceTest::_service
ros::ServiceServer _service
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:65
websocket_client.hpp
HELLO_WORLD_BINARY
constexpr uint8_t HELLO_WORLD_BINARY[]
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:18
foxglove::Client::publish
void publish(ClientChannelId channelId, const uint8_t *buffer, size_t size) override
Definition: websocket_client.hpp:180
param
T param(const std::string &param_name, const T &default_val)
foxglove::FetchAssetStatus::Error
@ Error
test_client.hpp
builtin_string.h
time_since_epoch
double time_since_epoch()
ParameterTest::PARAM_2_DEFAULT_VALUE
static const PARAM_2_TYPE PARAM_2_DEFAULT_VALUE
Definition: ros1_foxglove_bridge/tests/smoke_test.cpp:32
foxglove::FetchAssetStatus::Success
@ Success
ros::NodeHandle
foxglove::Service
Definition: common.hpp:121


foxglove_bridge
Author(s): Foxglove
autogenerated on Wed Mar 5 2025 03:34:31