Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Robustify spawner #1501

Merged
merged 22 commits into from
Aug 16, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
324a012
Add integration test with a lot of controller spawners
fmauch Apr 23, 2024
7ee0fad
Do not wait for controller_manager node
fmauch Apr 23, 2024
e25ea4f
Re-add controller_manager_timeout
fmauch Apr 23, 2024
c7bbbb5
Resolve deadlock in calling controller_manager services
fmauch Apr 23, 2024
9b4ecfc
Add missing controllers file
fmauch Apr 23, 2024
f26e536
Merge branch 'master' into robustify_spawner
destogl Aug 14, 2024
de424ac
Update controller_manager/controller_manager/controller_manager_servi…
destogl Aug 14, 2024
484cd4a
Add call_timeout parameter to service_caller
fmauch Aug 14, 2024
77f7e16
Add documentation to service_caller parameters
fmauch Aug 14, 2024
3e3aded
Make base_joint a revolute joint
fmauch Aug 14, 2024
85c593c
Use attempt counting with starting from 1
fmauch Aug 14, 2024
a98ca81
Add test_dependency on launch_testing_ament_cmake
fmauch Aug 14, 2024
aa0aa97
Correct error message on failed service call
fmauch Aug 14, 2024
2120fd8
Add more test dependencies
fmauch Aug 14, 2024
a77c600
Add used controllers to test dependencies
fmauch Aug 14, 2024
14028ea
Do not depend on other controllers
fmauch Aug 14, 2024
66ac4e8
Reduce installation scope
fmauch Aug 14, 2024
a117f8c
Fix test_ros2_control_node.yaml
fmauch Aug 14, 2024
723a896
Use gtest instead of launch_testing for integration test
fmauch Aug 15, 2024
26262c6
Revert sorting package.xml
fmauch Aug 15, 2024
49137f2
Revert fixing yaml
fmauch Aug 15, 2024
6d627b5
Apply suggestions from code review
fmauch Aug 15, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,39 @@ class ServiceNotFoundError(Exception):
pass


def service_caller(node, service_name, service_type, request, service_timeout=0.0):
def service_caller(
node,
service_name,
service_type,
request,
service_timeout=0.0,
call_timeout=10.0,
Comment on lines +40 to +41
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@fmauch one more question, do you see an easy way to make these configurable by the user? My bringup is quite CPU intensive causing the call_timeout to be reached, however it works if I increase it a bit

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If not, any harm in arbitrarily increasing it to e.g. 30?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

max_attempts=3,
):
"""
Abstraction of a service call.

Has an optional timeout to find the service, receive the answer to a call
and a mechanism to retry a call of no response is received.

@param node Node object to be associated with
@type rclpy.node.Node
@param service_name Service URL
@type str
@param request The request to be sent
@type service request type
@param service_timeout Timeout (in seconds) to wait until the service is available. 0 means
waiting forever, retrying every 10 seconds.
@type float
@param call_timeout Timeout (in seconds) for getting a response
@type float
@param max_attempts Number of attempts until a valid response is received. With some
middlewares it can happen, that the service response doesn't reach the client leaving it in
a waiting state forever.
@type int
@return The service response

"""
cli = node.create_client(service_type, service_name)

while not cli.service_is_ready():
Expand All @@ -44,12 +76,20 @@ def service_caller(node, service_name, service_type, request, service_timeout=0.
node.get_logger().warn(f"Could not contact service {service_name}")

node.get_logger().debug(f"requester: making request: {request}\n")
future = cli.call_async(request)
rclpy.spin_until_future_complete(node, future)
if future.result() is not None:
return future.result()
else:
raise RuntimeError(f"Exception while calling service: {future.exception()}")
future = None
for attempt in range(max_attempts):
future = cli.call_async(request)
rclpy.spin_until_future_complete(node, future, timeout_sec=call_timeout)
if future.result() is None:
node.get_logger().warning(
f"Failed getting a result from calling {service_name} in "
f"{service_timeout}. (Attempt {attempt+1} of {max_attempts}.)"
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@fmauch should be call_timeout right?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, that's right! Thanks for spotting this

)
else:
return future.result()
raise RuntimeError(
f"Could not successfully call service {service_name} after {max_attempts} attempts."
)


def configure_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
Expand Down
26 changes: 26 additions & 0 deletions controller_manager/test/test_spawner_unspawner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -374,6 +374,32 @@ TEST_F(TestLoadController, spawner_test_fallback_controllers)
}
}

TEST_F(TestLoadController, spawner_with_many_controllers)
{
std::stringstream ss;
const size_t num_controllers = 50;
const std::string controller_base_name = "ctrl_";
for (size_t i = 0; i < num_controllers; i++)
{
const std::string controller_name = controller_base_name + std::to_string(static_cast<int>(i));
cm_->set_parameter(
rclcpp::Parameter(controller_name + ".type", test_controller::TEST_CONTROLLER_CLASS_NAME));
ss << controller_name << " ";
}

ControllerManagerRunner cm_runner(this);
EXPECT_EQ(call_spawner(ss.str() + " -c test_controller_manager"), 0);

ASSERT_EQ(cm_->get_loaded_controllers().size(), num_controllers);

for (size_t i = 0; i < num_controllers; i++)
{
auto ctrl = cm_->get_loaded_controllers()[i];
ASSERT_EQ(ctrl.info.type, test_controller::TEST_CONTROLLER_CLASS_NAME);
ASSERT_EQ(ctrl.c->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
}
}

class TestLoadControllerWithoutRobotDescription
: public ControllerManagerFixture<controller_manager::ControllerManager>
{
Expand Down
Loading