ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
564 stars 427 forks source link

waiting for AsyncParametersClient's internal services to be ready #330

Closed BrannonKing closed 7 years ago

BrannonKing commented 7 years ago

When sending parameters to another node using AsyncParametersClient on top of CoreDX middleware, there is some delay between the constructor completing and the internal clients of AsyncParametersClient being ready. The individual client classes have service_is_ready and wait_for_service to deal with this issue, but they aren't exposed on the parameters client. Hence, I added the two methods shown below. If I run a tight loop on service_is_ready & spin_some, my internal clients are all ready to go in a few milliseconds. However, the wait_for_service method always takes the full timeout (but doesn't return false). It appears that the client wait_for_service method is waiting for a graph_changed event that never happens as these clients transition to ready. Is that a bug with rcl, rclcpp or rmw_coredx_cpp? Is there supposed to be a graph-changed event when a service/client's "is_ready" changes?

bool
AsyncParametersClient::service_is_ready() const
{
  return get_parameters_client_->service_is_ready()
      && get_parameter_types_client_->service_is_ready()
      && set_parameters_client_->service_is_ready()
      && list_parameters_client_->service_is_ready()
      && describe_parameters_client_->service_is_ready();
}

//template<typename RatioT> couldn't get this template to link properly for no obvious reason
bool
//AsyncParametersClient::wait_for_service(std::chrono::duration<int64_t, RatioT> timeout)
AsyncParametersClient::wait_for_service(std::chrono::nanoseconds timeout)
{
  const std::vector<std::shared_ptr<rclcpp::client::ClientBase>> clients =
  {
    get_parameters_client_,
    get_parameter_types_client_,
    set_parameters_client_,
    list_parameters_client_,
    describe_parameters_client_
  };
  for (auto& client: clients)
  {
    auto stamp = std::chrono::steady_clock::now();
    if (!client->wait_for_service(timeout))
      return false;
    if (timeout > std::chrono::nanoseconds::zero())
    {
      timeout -= std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::steady_clock::now() - stamp);
      if (timeout < std::chrono::nanoseconds::zero())
        timeout = std::chrono::nanoseconds::zero();
    }
  }
  return true;
}

You can see some other discussion on this here: https://github.com/tocinc/rmw_coredx/issues/8

BrannonKing commented 7 years ago

Is it possible that the lack of calling spin* while waiting for the graph event causes my problem? Maybe CoreDX can't prep its clients without some spin calls? I wanted to modify NodeGraph::wait_for_graph_change to call spin_once inside its predicate. However, I can't see how to access the executor in that context.

wjwwood commented 7 years ago

@BrannonKing you do not need to spin to wait for graph events because the necessary waiting is done in the GraphListener's thread, see:

https://github.com/ros2/rclcpp/blob/master/rclcpp/include/rclcpp/graph_listener.hpp https://github.com/ros2/rclcpp/blob/master/rclcpp/src/rclcpp/graph_listener.cpp#L166

wjwwood commented 7 years ago

Make sure the test_graph test in the rcl package passes with CoreDX.

BrannonKing commented 7 years ago

test_graph passed. I do see this one fail: test_get_node_names__rmw_coredx_cpp

wjwwood commented 7 years ago

I don't have any other ideas. If this feature works in Fast-RTPS and Connext and test_graph passes, then I guess it must be a gap in the test_graph tests.

Is it possible for you to test one of our other rmw implementations, like Fast-RTPS?

BrannonKing commented 7 years ago

I recompiled this today and it seems to work with both Fast-RTPS and CoreDX. I don't know why it didn't work with CoreDX before; perhaps something in the framework has changed over the past two weeks to resolve that stall I was seeing. I also found my linkage problem. I've put in a pull request for the above methods: https://github.com/ros2/rclcpp/pull/337

dirk-thomas commented 7 years ago

I recompiled this today and it seems to work with both Fast-RTPS and CoreDX.

@BrannonKing Can this be closed?

BrannonKing commented 7 years ago

Now that the wait_for_service method is available, we should call it from the parameter CLI tool.

dirk-thomas commented 7 years ago

The current parameter CLI tool is written in C++ and we don't plan to spend any time on it. The goal is to replace it with a Python implementation in the ros2cli framework as soon as parameters are implemented in rclpy.

BrannonKing commented 7 years ago

Let's use it in the Python impelmentation, then. I may put in a pull request for the current tool. At ASI we're using a separate tool that loads params from YAML. The wait method will help us there.