Skip to content

Commit

Permalink
changes after rebase
Browse files Browse the repository at this point in the history
Signed-off-by: Karsten Knese <Karsten1987@users.noreply.github.com>
  • Loading branch information
Karsten1987 committed Nov 2, 2020
1 parent 7d0b061 commit 310d320
Show file tree
Hide file tree
Showing 8 changed files with 86 additions and 84 deletions.
58 changes: 29 additions & 29 deletions controller_manager/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,24 +70,24 @@ class ResourceStorage
}

template<class HardwareT>
void import_state_handles(HardwareT & hardware)
void import_state_interfaces(HardwareT & hardware)
{
auto handles = hardware.export_state_handles();
for (auto i = 0u; i < handles.size(); ++i) {
auto key = handles[i].get_name() + "/" + handles[i].get_interface_name();
state_handle_map_.emplace(
std::make_pair(key, std::move(handles[i])));
auto interfaces = hardware.export_state_interfaces();
for (auto i = 0u; i < interfaces.size(); ++i) {
auto key = interfaces[i].get_name() + "/" + interfaces[i].get_interface_name();
state_interface_map_.emplace(
std::make_pair(key, std::move(interfaces[i])));
}
}

template<class HardwareT>
void import_command_handles(HardwareT & hardware)
void import_command_interfaces(HardwareT & hardware)
{
auto handles = hardware.export_command_handles();
for (auto i = 0u; i < handles.size(); ++i) {
auto key = handles[i].get_name() + "/" + handles[i].get_interface_name();
command_handle_map_.emplace(
std::make_pair(key, std::move(handles[i])));
auto interfaces = hardware.export_command_interfaces();
for (auto i = 0u; i < interfaces.size(); ++i) {
auto key = interfaces[i].get_name() + "/" + interfaces[i].get_interface_name();
command_interface_map_.emplace(
std::make_pair(key, std::move(interfaces[i])));
}
}

Expand All @@ -99,8 +99,8 @@ class ResourceStorage
if (hardware_interface::return_type::OK != actuators_.back().configure(hardware_info)) {
throw std::runtime_error(std::string("failed to configure ") + hardware_info.name);
}
import_state_handles(actuators_.back());
import_command_handles(actuators_.back());
import_state_interfaces(actuators_.back());
import_command_interfaces(actuators_.back());
}

void initialize_sensor(const hardware_interface::HardwareInfo & hardware_info)
Expand All @@ -109,7 +109,7 @@ class ResourceStorage
hardware_interface::components::SensorInterface>(
hardware_info, sensor_loader_, sensors_);
sensors_.back().configure(hardware_info);
import_state_handles(sensors_.back());
import_state_interfaces(sensors_.back());
}

void initialize_system(const hardware_interface::HardwareInfo & hardware_info)
Expand All @@ -118,8 +118,8 @@ class ResourceStorage
hardware_interface::components::SystemInterface>(
hardware_info, system_loader_, systems_);
systems_.back().configure(hardware_info);
import_state_handles(systems_.back());
import_command_handles(systems_.back());
import_state_interfaces(systems_.back());
import_command_interfaces(systems_.back());
}

// hardware plugins
Expand All @@ -131,8 +131,8 @@ class ResourceStorage
std::vector<hardware_interface::components::Sensor> sensors_;
std::vector<hardware_interface::components::System> systems_;

std::unordered_map<std::string, hardware_interface::StateHandle> state_handle_map_;
std::unordered_map<std::string, hardware_interface::CommandHandle> command_handle_map_;
std::unordered_map<std::string, hardware_interface::StateInterface> state_interface_map_;
std::unordered_map<std::string, hardware_interface::CommandInterface> command_interface_map_;
};

ResourceManager::ResourceManager()
Expand Down Expand Up @@ -163,34 +163,34 @@ ResourceManager::ResourceManager(const std::string & urdf)
}
}

std::vector<std::string> ResourceManager::state_handle_keys() const
std::vector<std::string> ResourceManager::state_interface_keys() const
{
std::vector<std::string> keys;
for (const auto & item : resource_storage_->state_handle_map_) {
for (const auto & item : resource_storage_->state_interface_map_) {
keys.push_back(std::get<0>(item));
}
return keys;
}

bool ResourceManager::state_handle_exists(const std::string & key) const
bool ResourceManager::state_interface_exists(const std::string & key) const
{
return resource_storage_->state_handle_map_.find(key) !=
resource_storage_->state_handle_map_.end();
return resource_storage_->state_interface_map_.find(key) !=
resource_storage_->state_interface_map_.end();
}

std::vector<std::string> ResourceManager::command_handle_keys() const
std::vector<std::string> ResourceManager::command_interface_keys() const
{
std::vector<std::string> keys;
for (const auto & item : resource_storage_->command_handle_map_) {
for (const auto & item : resource_storage_->command_interface_map_) {
keys.push_back(std::get<0>(item));
}
return keys;
}

bool ResourceManager::command_handle_exists(const std::string & key) const
bool ResourceManager::command_interface_exists(const std::string & key) const
{
return resource_storage_->command_handle_map_.find(key) !=
resource_storage_->command_handle_map_.end();
return resource_storage_->command_interface_map_.find(key) !=
resource_storage_->command_interface_map_.end();
}

size_t ResourceManager::actuator_interfaces_size() const
Expand Down
20 changes: 10 additions & 10 deletions controller_manager/src/resource_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,33 +35,33 @@ class ResourceManager

~ResourceManager();

/// Returns all registered state handles keys.
/// Returns all registered state interfaces keys.
/**
* The keys are collected from each loaded hardware component.
*
* \return vector of strings, containing all registered keys.
*/
std::vector<std::string> state_handle_keys() const;
std::vector<std::string> state_interface_keys() const;

/// Checks whether a handle is registered under the given key.
/// Checks whether a interface is registered under the given key.
/**
* \return true if handle exist, false otherwise.
* \return true if interface exist, false otherwise.
*/
bool state_handle_exists(const std::string & key) const;
bool state_interface_exists(const std::string & key) const;

/// Returns all registered command handles keys.
/// Returns all registered command interfaces keys.
/**
* The keys are collected from each loaded hardware component.
*
* \return vector of strings, containing all registered keys.
*/
std::vector<std::string> command_handle_keys() const;
std::vector<std::string> command_interface_keys() const;

/// Checks whether a handle is registered under the given key.
/// Checks whether a interface is registered under the given key.
/**
* \return true if handle exist, false otherwise.
* \return true if interface exist, false otherwise.
*/
bool command_handle_exists(const std::string & key) const;
bool command_interface_exists(const std::string & key) const;

/// Return the number of loaded actuator components.
/**
Expand Down
28 changes: 14 additions & 14 deletions controller_manager/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

using hardware_interface::status;
using hardware_interface::return_type;
using hardware_interface::StateHandle;
using hardware_interface::CommandHandle;
using hardware_interface::StateInterface;
using hardware_interface::CommandInterface;

class TestActuator : public hardware_interface::components::ActuatorInterface
{
Expand All @@ -37,33 +37,33 @@ class TestActuator : public hardware_interface::components::ActuatorInterface
return return_type::OK;
}

std::vector<StateHandle> export_state_handles() override
std::vector<StateInterface> export_state_interfaces() override
{
std::vector<StateHandle> state_handles;
state_handles.emplace_back(
hardware_interface::StateHandle(
std::vector<StateInterface> state_interfaces;
state_interfaces.emplace_back(
hardware_interface::StateInterface(
actuator_info_.joints[0].name,
actuator_info_.joints[0].state_interfaces[0].name,
&position_state_));
state_handles.emplace_back(
hardware_interface::StateHandle(
state_interfaces.emplace_back(
hardware_interface::StateInterface(
actuator_info_.joints[0].name,
actuator_info_.joints[0].state_interfaces[1].name,
&velocity_state_));

return state_handles;
return state_interfaces;
}

std::vector<CommandHandle> export_command_handles() override
std::vector<CommandInterface> export_command_interfaces() override
{
std::vector<CommandHandle> command_handles;
command_handles.emplace_back(
hardware_interface::CommandHandle(
std::vector<CommandInterface> command_interfaces;
command_interfaces.emplace_back(
hardware_interface::CommandInterface(
actuator_info_.joints[0].name,
actuator_info_.joints[0].command_interfaces[0].name,
&velocity_command_));

return command_handles;
return command_interfaces;
}

return_type start() override
Expand Down
12 changes: 6 additions & 6 deletions controller_manager/test/test_components/test_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

using hardware_interface::status;
using hardware_interface::return_type;
using hardware_interface::StateHandle;
using hardware_interface::StateInterface;

class TestSensor : public hardware_interface::components::SensorInterface
{
Expand All @@ -31,16 +31,16 @@ class TestSensor : public hardware_interface::components::SensorInterface
return return_type::OK;
}

std::vector<StateHandle> export_state_handles() override
std::vector<StateInterface> export_state_interfaces() override
{
std::vector<StateHandle> state_handles;
state_handles.emplace_back(
hardware_interface::StateHandle(
std::vector<StateInterface> state_interfaces;
state_interfaces.emplace_back(
hardware_interface::StateInterface(
sensor_info_.sensors[0].name,
sensor_info_.sensors[0].state_interfaces[0].name,
&velocity_state_));

return state_handles;
return state_interfaces;
}

return_type start() override
Expand Down
24 changes: 12 additions & 12 deletions controller_manager/test/test_components/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@

using hardware_interface::status;
using hardware_interface::return_type;
using hardware_interface::StateHandle;
using hardware_interface::CommandHandle;
using hardware_interface::StateInterface;
using hardware_interface::CommandInterface;

class TestSystem : public hardware_interface::components::SystemInterface
{
Expand All @@ -31,28 +31,28 @@ class TestSystem : public hardware_interface::components::SystemInterface
return return_type::OK;
}

std::vector<StateHandle> export_state_handles() override
std::vector<StateInterface> export_state_interfaces() override
{
std::vector<StateHandle> state_handles;
std::vector<StateInterface> state_interfaces;
for (auto i = 0u; i < system_info_.joints.size(); ++i) {
state_handles.emplace_back(
hardware_interface::StateHandle(
state_interfaces.emplace_back(
hardware_interface::StateInterface(
system_info_.joints[i].name, "position", &position_state_[i]));
}

return state_handles;
return state_interfaces;
}

std::vector<CommandHandle> export_command_handles() override
std::vector<CommandInterface> export_command_interfaces() override
{
std::vector<CommandHandle> command_handles;
std::vector<CommandInterface> command_interfaces;
for (auto i = 0u; i < system_info_.joints.size(); ++i) {
command_handles.emplace_back(
hardware_interface::CommandHandle(
command_interfaces.emplace_back(
hardware_interface::CommandInterface(
system_info_.joints[i].name, "velocity", &velocity_command_[i]));
}

return command_handles;
return command_interfaces;
}

return_type start() override
Expand Down
24 changes: 12 additions & 12 deletions controller_manager/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,17 +146,17 @@ TEST_F(TestResourceManager, initialization_with_urdf) {
EXPECT_EQ(1u, rm.sensor_interfaces_size());
EXPECT_EQ(1u, rm.system_interfaces_size());

auto state_handle_keys = rm.state_handle_keys();
ASSERT_EQ(5u, state_handle_keys.size());
EXPECT_TRUE(rm.state_handle_exists("joint1/position"));
EXPECT_TRUE(rm.state_handle_exists("joint1/velocity"));
EXPECT_TRUE(rm.state_handle_exists("sensor1/velocity"));
EXPECT_TRUE(rm.state_handle_exists("joint2/position"));
EXPECT_TRUE(rm.state_handle_exists("joint3/position"));
auto state_interface_keys = rm.state_interface_keys();
ASSERT_EQ(5u, state_interface_keys.size());
EXPECT_TRUE(rm.state_interface_exists("joint1/position"));
EXPECT_TRUE(rm.state_interface_exists("joint1/velocity"));
EXPECT_TRUE(rm.state_interface_exists("sensor1/velocity"));
EXPECT_TRUE(rm.state_interface_exists("joint2/position"));
EXPECT_TRUE(rm.state_interface_exists("joint3/position"));

auto command_handle_keys = rm.command_handle_keys();
ASSERT_EQ(3u, command_handle_keys.size());
EXPECT_TRUE(rm.command_handle_exists("joint1/position"));
EXPECT_TRUE(rm.command_handle_exists("joint2/velocity"));
EXPECT_TRUE(rm.command_handle_exists("joint3/velocity"));
auto command_interface_keys = rm.command_interface_keys();
ASSERT_EQ(3u, command_interface_keys.size());
EXPECT_TRUE(rm.command_interface_exists("joint1/position"));
EXPECT_TRUE(rm.command_interface_exists("joint2/velocity"));
EXPECT_TRUE(rm.command_interface_exists("joint3/velocity"));
}
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ class System final
HARDWARE_INTERFACE_PUBLIC
explicit System(std::unique_ptr<SystemInterface> impl);

System(System && other) = default;

~System() = default;

HARDWARE_INTERFACE_PUBLIC
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/include/hardware_interface/handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class ReadOnlyHandle
const std::string & name,
const std::string & interface_name,
double * value_ptr = nullptr)
: name_(std::move(name)), interface_name_(std::move(interface_name)), value_ptr_(value_ptr)
: name_(name), interface_name_(interface_name), value_ptr_(value_ptr)
{
}

Expand Down

0 comments on commit 310d320

Please sign in to comment.