Browse Source

Add some example service requests to C++ ROS2 example

tags/v0.3.3-rc1
Philipp Oppermann 1 year ago
parent
commit
b16a7cd3a1
Failed to extract signature
1 changed files with 21 additions and 0 deletions
  1. +21
    -0
      examples/c++-ros2-dataflow/node-rust-api/main.cc

+ 21
- 0
examples/c++-ros2-dataflow/node-rust-api/main.cc View File

@@ -29,7 +29,15 @@ int main()
std::default_random_engine gen(dev());
std::uniform_real_distribution<> dist(0., 1.);

auto service_qos = qos_default();
service_qos.reliable = true;
service_qos.max_blocking_time = 0.1;
service_qos.keep_last = 1;
auto add_two_ints = node->create_client_example_interfaces_AddTwoInts("/", "add_two_ints", service_qos, merged_events);
add_two_ints->wait_for_service(node);

auto received_ticks = 0;
auto responses_received = 0;

for (int i = 0; i < 1000; i++)
{
@@ -56,6 +64,9 @@ int main()
.linear = {.x = dist(gen) + 1, .y = 0, .z = 0},
.angular = {.x = 0, .y = 0, .z = (dist(gen) - 0.5) * 5.0}};
vel_publisher->publish(twist);

example_interfaces::AddTwoInts_Request request = {.a = 4, .b = 5};
add_two_ints->send_request(request);
}
else
{
@@ -72,12 +83,22 @@ int main()
auto pose = pose_subscription->downcast(std::move(event));
std::cout << "Received pose x:" << pose.x << ", y:" << pose.y << std::endl;
}
else if (add_two_ints->matches(event))
{
auto response = add_two_ints->downcast(std::move(event));
assert(response.sum == 9);
std::cout << "Received correct sum response from add_two_ints" << std::endl;
responses_received += 1;
}
else
{
std::cout << "received unexpected event" << std::endl;
}
}

std::cout << "Received " << responses_received << " service responses" << std::endl;
assert(responses_received > 0);

// try to access a constant for testing
assert((sensor_msgs::const_NavSatStatus_STATUS_NO_FIX() == -1));



Loading…
Cancel
Save