Skip to content

Commit

Permalink
Merge branch 'master' into cli/add/params_file_arg
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Aug 16, 2024
2 parents 3e62e81 + 80c264f commit 6592413
Show file tree
Hide file tree
Showing 4 changed files with 118 additions and 50 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,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,
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 @@ -67,12 +99,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}.)"
)
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 @@ -367,6 +367,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
80 changes: 41 additions & 39 deletions hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,41 +16,45 @@
#define HARDWARE_INTERFACE__HANDLE_HPP_

#include <string>
#include <variant>

#include "hardware_interface/macros.hpp"

namespace hardware_interface
{

using HANDLE_DATATYPE = std::variant<double>;

/// A handle used to get and set a value on a given interface.
class ReadOnlyHandle
class Handle
{
public:
ReadOnlyHandle(
Handle(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: prefix_name_(prefix_name), interface_name_(interface_name), value_ptr_(value_ptr)
{
}

explicit ReadOnlyHandle(const std::string & interface_name)
explicit Handle(const std::string & interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
{
}

explicit ReadOnlyHandle(const char * interface_name)
explicit Handle(const char * interface_name)
: interface_name_(interface_name), value_ptr_(nullptr)
{
}

ReadOnlyHandle(const ReadOnlyHandle & other) = default;
Handle(const Handle & other) = default;

ReadOnlyHandle(ReadOnlyHandle && other) = default;
Handle(Handle && other) = default;

ReadOnlyHandle & operator=(const ReadOnlyHandle & other) = default;
Handle & operator=(const Handle & other) = default;

ReadOnlyHandle & operator=(ReadOnlyHandle && other) = default;
Handle & operator=(Handle && other) = default;

virtual ~ReadOnlyHandle() = default;
virtual ~Handle() = default;

/// Returns true if handle references a value.
inline operator bool() const { return value_ptr_ != nullptr; }
Expand All @@ -70,60 +74,58 @@ class ReadOnlyHandle

double get_value() const
{
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) return value_ if old functionality is removed
THROW_ON_NULLPTR(value_ptr_);
return *value_ptr_;
// END
}

void set_value(double value)
{
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) set value_ directly if old functionality is removed
THROW_ON_NULLPTR(this->value_ptr_);
*this->value_ptr_ = value;
// END
}

protected:
std::string prefix_name_;
std::string interface_name_;
HANDLE_DATATYPE value_;
// BEGIN (Handle export change): for backward compatibility
// TODO(Manuel) redeclare as HANDLE_DATATYPE * value_ptr_ if old functionality is removed
double * value_ptr_;
// END
};

class ReadWriteHandle : public ReadOnlyHandle
class StateInterface : public Handle
{
public:
ReadWriteHandle(
explicit StateInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: ReadOnlyHandle(prefix_name, interface_name, value_ptr)
{
}

explicit ReadWriteHandle(const std::string & interface_name) : ReadOnlyHandle(interface_name) {}

explicit ReadWriteHandle(const char * interface_name) : ReadOnlyHandle(interface_name) {}

ReadWriteHandle(const ReadWriteHandle & other) = default;

ReadWriteHandle(ReadWriteHandle && other) = default;

ReadWriteHandle & operator=(const ReadWriteHandle & other) = default;

ReadWriteHandle & operator=(ReadWriteHandle && other) = default;

virtual ~ReadWriteHandle() = default;

void set_value(double value)
: Handle(prefix_name, interface_name, value_ptr)
{
THROW_ON_NULLPTR(this->value_ptr_);
*this->value_ptr_ = value;
}
};

class StateInterface : public ReadOnlyHandle
{
public:
StateInterface(const StateInterface & other) = default;

StateInterface(StateInterface && other) = default;

using ReadOnlyHandle::ReadOnlyHandle;
using Handle::Handle;
};

class CommandInterface : public ReadWriteHandle
class CommandInterface : public Handle
{
public:
explicit CommandInterface(
const std::string & prefix_name, const std::string & interface_name,
double * value_ptr = nullptr)
: Handle(prefix_name, interface_name, value_ptr)
{
}
/// CommandInterface copy constructor is actively deleted.
/**
* Command interfaces are having a unique ownership and thus
Expand All @@ -134,7 +136,7 @@ class CommandInterface : public ReadWriteHandle

CommandInterface(CommandInterface && other) = default;

using ReadWriteHandle::ReadWriteHandle;
using Handle::Handle;
};

} // namespace hardware_interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,17 +20,17 @@
namespace transmission_interface
{
/** A handle used to get and set a value on a given actuator interface. */
class ActuatorHandle : public hardware_interface::ReadWriteHandle
class ActuatorHandle : public hardware_interface::Handle
{
public:
using hardware_interface::ReadWriteHandle::ReadWriteHandle;
using hardware_interface::Handle::Handle;
};

/** A handle used to get and set a value on a given joint interface. */
class JointHandle : public hardware_interface::ReadWriteHandle
class JointHandle : public hardware_interface::Handle
{
public:
using hardware_interface::ReadWriteHandle::ReadWriteHandle;
using hardware_interface::Handle::Handle;
};

} // namespace transmission_interface
Expand Down

0 comments on commit 6592413

Please sign in to comment.