Skip to content

Commit

Permalink
Merge branch 'master' into add/hw_components/update_rate
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jul 5, 2024
2 parents 84d00da + 723c869 commit 2540431
Show file tree
Hide file tree
Showing 25 changed files with 1,675 additions and 243 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_

#include <string>
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
Expand Down Expand Up @@ -55,6 +56,9 @@ class ChainableControllerInterface : public ControllerInterfaceBase
CONTROLLER_INTERFACE_PUBLIC
bool is_chainable() const final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface> export_state_interfaces() final;

CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::CommandInterface> export_reference_interfaces() final;

Expand All @@ -65,16 +69,27 @@ class ChainableControllerInterface : public ControllerInterfaceBase
bool is_in_chained_mode() const final;

protected:
/// Virtual method that each chainable controller should implement to export its chainable
/// interfaces.
/// Virtual method that each chainable controller should implement to export its read-only
/// chainable interfaces.
/**
* Each chainable controller implements this methods where all its state(read only) interfaces are
* exported. The method has the same meaning as `export_state_interfaces` method from
* hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.
*
* \returns list of StateInterfaces that other controller can use as their inputs.
*/
virtual std::vector<hardware_interface::StateInterface> on_export_state_interfaces();

/// Virtual method that each chainable controller should implement to export its read/write
/// chainable interfaces.
/**
* Each chainable controller implements this methods where all input (command) interfaces are
* exported. The method has the same meaning as `export_command_interface` method from
* hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.
*
* \returns list of CommandInterfaces that other controller can use as their outputs.
*/
virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() = 0;
virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();

/// Virtual method that each chainable controller should implement to switch chained mode.
/**
Expand Down Expand Up @@ -114,7 +129,12 @@ class ChainableControllerInterface : public ControllerInterfaceBase
virtual return_type update_and_write_commands(
const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

/// Storage of values for state interfaces
std::vector<std::string> exported_state_interface_names_;
std::vector<double> state_interfaces_values_;

/// Storage of values for reference interfaces
std::vector<std::string> exported_reference_interface_names_;
std::vector<double> reference_interfaces_;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,14 @@ class ControllerInterface : public controller_interface::ControllerInterfaceBase
CONTROLLER_INTERFACE_PUBLIC
bool is_chainable() const final;

/**
* A non-chainable controller doesn't export any state interfaces.
*
* \returns empty list.
*/
CONTROLLER_INTERFACE_PUBLIC
std::vector<hardware_interface::StateInterface> export_state_interfaces() final;

/**
* Controller has no reference interfaces.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -224,11 +224,20 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual std::vector<hardware_interface::CommandInterface> export_reference_interfaces() = 0;

/**
* Export interfaces for a chainable controller that can be used as state interface by other
* controllers.
*
* \returns list of state interfaces for preceding controllers.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual std::vector<hardware_interface::StateInterface> export_state_interfaces() = 0;

/**
* Set chained mode of a chainable controller. This method triggers internal processes to switch
* a chainable controller to "chained" mode and vice-versa. Setting controller to "chained" mode
* usually involves disabling of subscribers and other external interfaces to avoid potential
* concurrency in input commands.
* usually involves the usage of the controller's reference interfaces by the other
* controllers
*
* \returns true if mode is switched successfully and false if not.
*/
Expand Down
65 changes: 50 additions & 15 deletions controller_interface/src/chainable_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,26 +44,35 @@ return_type ChainableControllerInterface::update(
return ret;
}

std::vector<hardware_interface::CommandInterface>
ChainableControllerInterface::export_reference_interfaces()
std::vector<hardware_interface::StateInterface>
ChainableControllerInterface::export_state_interfaces()
{
auto reference_interfaces = on_export_reference_interfaces();
auto state_interfaces = on_export_state_interfaces();

// check if the "reference_interfaces_" variable is resized to number of interfaces
if (reference_interfaces_.size() != reference_interfaces.size())
// check if the names of the controller state interfaces begin with the controller's name
for (const auto & interface : state_interfaces)
{
// TODO(destogl): Should here be "FATAL"? It is fatal in terms of controller but not for the
// framework
RCLCPP_FATAL(
get_node()->get_logger(),
"The internal storage for reference values 'reference_interfaces_' variable has size '%zu', "
"but it is expected to have the size '%zu' equal to the number of exported reference "
"interfaces. No reference interface will be exported. Please correct and recompile "
"the controller with name '%s' and try again.",
reference_interfaces_.size(), reference_interfaces.size(), get_node()->get_name());
reference_interfaces.clear();
if (interface.get_prefix_name() != get_node()->get_name())
{
RCLCPP_FATAL(
get_node()->get_logger(),
"The name of the interface '%s' does not begin with the controller's name. This is "
"mandatory for state interfaces. No state interface will be exported. Please "
"correct and recompile the controller with name '%s' and try again.",
interface.get_name().c_str(), get_node()->get_name());
state_interfaces.clear();
break;
}
}

return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
ChainableControllerInterface::export_reference_interfaces()
{
auto reference_interfaces = on_export_reference_interfaces();

// check if the names of the reference interfaces begin with the controller's name
for (const auto & interface : reference_interfaces)
{
Expand Down Expand Up @@ -113,4 +122,30 @@ bool ChainableControllerInterface::is_in_chained_mode() const { return in_chaine

bool ChainableControllerInterface::on_set_chained_mode(bool /*chained_mode*/) { return true; }

std::vector<hardware_interface::StateInterface>
ChainableControllerInterface::on_export_state_interfaces()
{
state_interfaces_values_.resize(exported_state_interface_names_.size(), 0.0);
std::vector<hardware_interface::StateInterface> state_interfaces;
for (size_t i = 0; i < exported_state_interface_names_.size(); ++i)
{
state_interfaces.emplace_back(hardware_interface::StateInterface(
get_node()->get_name(), exported_state_interface_names_[i], &state_interfaces_values_[i]));
}
return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
ChainableControllerInterface::on_export_reference_interfaces()
{
reference_interfaces_.resize(exported_reference_interface_names_.size(), 0.0);
std::vector<hardware_interface::CommandInterface> reference_interfaces;
for (size_t i = 0; i < exported_reference_interface_names_.size(); ++i)
{
reference_interfaces.emplace_back(hardware_interface::CommandInterface(
get_node()->get_name(), exported_reference_interface_names_[i], &reference_interfaces_[i]));
}
return reference_interfaces;
}

} // namespace controller_interface
5 changes: 5 additions & 0 deletions controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,11 @@ ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {}

bool ControllerInterface::is_chainable() const { return false; }

std::vector<hardware_interface::StateInterface> ControllerInterface::export_state_interfaces()
{
return {};
}

std::vector<hardware_interface::CommandInterface> ControllerInterface::export_reference_interfaces()
{
return {};
Expand Down
47 changes: 34 additions & 13 deletions controller_interface/test/test_chainable_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@

#include <gmock/gmock.h>

using ::testing::IsEmpty;
using ::testing::SizeIs;

TEST_F(ChainableControllerInterfaceTest, default_returns)
{
TestableChainableControllerInterface controller;
Expand All @@ -31,7 +34,7 @@ TEST_F(ChainableControllerInterfaceTest, default_returns)
EXPECT_FALSE(controller.is_in_chained_mode());
}

TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces)
TEST_F(ChainableControllerInterfaceTest, export_state_interfaces)
{
TestableChainableControllerInterface controller;

Expand All @@ -42,16 +45,16 @@ TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces)
controller_interface::return_type::OK);
ASSERT_NO_THROW(controller.get_node());

auto reference_interfaces = controller.export_reference_interfaces();
auto exported_state_interfaces = controller.export_state_interfaces();

ASSERT_EQ(reference_interfaces.size(), 1u);
EXPECT_EQ(reference_interfaces[0].get_prefix_name(), TEST_CONTROLLER_NAME);
EXPECT_EQ(reference_interfaces[0].get_interface_name(), "test_itf");
ASSERT_THAT(exported_state_interfaces, SizeIs(1));
EXPECT_EQ(exported_state_interfaces[0].get_prefix_name(), TEST_CONTROLLER_NAME);
EXPECT_EQ(exported_state_interfaces[0].get_interface_name(), "test_state");

EXPECT_EQ(reference_interfaces[0].get_value(), INTERFACE_VALUE);
EXPECT_EQ(exported_state_interfaces[0].get_value(), EXPORTED_STATE_INTERFACE_VALUE);
}

TEST_F(ChainableControllerInterfaceTest, reference_interfaces_storage_not_correct_size)
TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces)
{
TestableChainableControllerInterface controller;

Expand All @@ -62,13 +65,16 @@ TEST_F(ChainableControllerInterfaceTest, reference_interfaces_storage_not_correc
controller_interface::return_type::OK);
ASSERT_NO_THROW(controller.get_node());

// expect empty return because storage is not resized
controller.reference_interfaces_.clear();
auto reference_interfaces = controller.export_reference_interfaces();
ASSERT_TRUE(reference_interfaces.empty());

ASSERT_THAT(reference_interfaces, SizeIs(1));
EXPECT_EQ(reference_interfaces[0].get_prefix_name(), TEST_CONTROLLER_NAME);
EXPECT_EQ(reference_interfaces[0].get_interface_name(), "test_itf");

EXPECT_EQ(reference_interfaces[0].get_value(), INTERFACE_VALUE);
}

TEST_F(ChainableControllerInterfaceTest, reference_interfaces_prefix_is_not_node_name)
TEST_F(ChainableControllerInterfaceTest, interfaces_prefix_is_not_node_name)
{
TestableChainableControllerInterface controller;

Expand All @@ -83,7 +89,10 @@ TEST_F(ChainableControllerInterfaceTest, reference_interfaces_prefix_is_not_node

// expect empty return because interface prefix is not equal to the node name
auto reference_interfaces = controller.export_reference_interfaces();
ASSERT_TRUE(reference_interfaces.empty());
ASSERT_THAT(reference_interfaces, IsEmpty());
// expect empty return because interface prefix is not equal to the node name
auto exported_state_interfaces = controller.export_state_interfaces();
ASSERT_THAT(exported_state_interfaces, IsEmpty());
}

TEST_F(ChainableControllerInterfaceTest, setting_chained_mode)
Expand All @@ -98,12 +107,15 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode)
ASSERT_NO_THROW(controller.get_node());

auto reference_interfaces = controller.export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), 1u);
ASSERT_THAT(reference_interfaces, SizeIs(1));
auto exported_state_interfaces = controller.export_state_interfaces();
ASSERT_THAT(exported_state_interfaces, SizeIs(1));

EXPECT_FALSE(controller.is_in_chained_mode());

// Fail setting chained mode
EXPECT_EQ(reference_interfaces[0].get_value(), INTERFACE_VALUE);
EXPECT_EQ(exported_state_interfaces[0].get_value(), EXPORTED_STATE_INTERFACE_VALUE);

EXPECT_FALSE(controller.set_chained_mode(true));
EXPECT_FALSE(controller.is_in_chained_mode());
Expand All @@ -116,6 +128,7 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode)

EXPECT_TRUE(controller.set_chained_mode(true));
EXPECT_TRUE(controller.is_in_chained_mode());
EXPECT_EQ(exported_state_interfaces[0].get_value(), EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE);

controller.configure();
EXPECT_TRUE(controller.set_chained_mode(false));
Expand Down Expand Up @@ -147,27 +160,31 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic)
controller_interface::return_type::OK);
ASSERT_NO_THROW(controller.get_node());

EXPECT_FALSE(controller.set_chained_mode(false));
EXPECT_FALSE(controller.is_in_chained_mode());

// call update and update it from subscriber because not in chained mode
ASSERT_EQ(
controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_INITIAL_REF - 1);
ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1);

// Provoke error in update from subscribers - return ERROR and update_and_write_commands not exec.
controller.set_new_reference_interface_value(INTERFACE_VALUE_SUBSCRIBER_ERROR);
ASSERT_EQ(
controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::ERROR);
ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_INITIAL_REF - 1);
ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1);

// Provoke error from update - return ERROR, but reference interface is updated and not reduced
controller.set_new_reference_interface_value(INTERFACE_VALUE_UPDATE_ERROR);
ASSERT_EQ(
controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::ERROR);
ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_UPDATE_ERROR);
ASSERT_EQ(controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE + 1);

controller.reference_interfaces_[0] = 0.0;

Expand All @@ -181,6 +198,8 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic)
controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
ASSERT_EQ(controller.reference_interfaces_[0], -1.0);
ASSERT_EQ(
controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE + 1);

// Provoke error from update - return ERROR, but reference interface is updated directly
controller.set_new_reference_interface_value(INTERFACE_VALUE_SUBSCRIBER_ERROR);
Expand All @@ -189,4 +208,6 @@ TEST_F(ChainableControllerInterfaceTest, test_update_logic)
controller.update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::ERROR);
ASSERT_EQ(controller.reference_interfaces_[0], INTERFACE_VALUE_UPDATE_ERROR);
ASSERT_EQ(
controller.state_interfaces_values_[0], EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE + 1);
}
Loading

0 comments on commit 2540431

Please sign in to comment.