Skip to content
This repository has been archived by the owner on Mar 3, 2020. It is now read-only.

Commit

Permalink
Merge pull request ros-controls#1 from Karsten1987/ros2_master_api
Browse files Browse the repository at this point in the history
Ros2 master api
  • Loading branch information
parthc-rob authored Jun 20, 2018
2 parents ac926c4 + cb2239f commit f15717f
Show file tree
Hide file tree
Showing 7 changed files with 40 additions and 73 deletions.
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "ament_index_cpp/get_resource.hpp"
#include "ament_index_cpp/get_resources.hpp"

#include "class_loader/class_loader.h"
#include "class_loader/class_loader.hpp"

#include "controller_interface/controller_interface.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ TestController::on_configure(const rclcpp_lifecycle::State & previous_state)

} // namespace test_controller

#include "class_loader/class_loader_register_macro.h"
#include "class_loader/register_macro.hpp"

CLASS_LOADER_REGISTER_CLASS(
test_controller::TestController, controller_interface::ControllerInterface)
Original file line number Diff line number Diff line change
Expand Up @@ -35,20 +35,13 @@ class ParameterServer : public rclcpp::Node
virtual
~ParameterServer() = default;

CONTROLLER_PARAMETER_SERVER_PUBLIC
void
init();

CONTROLLER_PARAMETER_SERVER_PUBLIC
void
load_parameters(const std::string & yaml_config_file);

CONTROLLER_PARAMETER_SERVER_PUBLIC
void
load_parameters(const std::string & key, const std::string & value);

private:
std::shared_ptr<rclcpp::ParameterService> parameter_service_;
};

} // namespace controller_parameter_server
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ int main(int argc, char ** argv)
}

auto ps = std::make_shared<controller_parameter_server::ParameterServer>();
ps->init();
ps->load_parameters(argv[1]);

rclcpp::spin(ps);
Expand Down
19 changes: 2 additions & 17 deletions controller_parameter_server/src/parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,20 +25,9 @@ ParameterServer::ParameterServer()
: rclcpp::Node("controller_parameter_server")
{}

void
ParameterServer::init()
{
parameter_service_ =
std::make_shared<rclcpp::ParameterService>(shared_from_this());
}

void
ParameterServer::load_parameters(const std::string & yaml_config_file)
{
if (!parameter_service_) {
throw std::runtime_error("parameter server is not initialized");
}

if (yaml_config_file.empty()) {
throw std::runtime_error("yaml config file path is empty");
}
Expand All @@ -48,18 +37,14 @@ ParameterServer::load_parameters(const std::string & yaml_config_file)

auto key_values = parser.get_key_value_pairs();
for (auto pair : key_values) {
this->set_parameters({rclcpp::parameter::ParameterVariant(pair.first, pair.second)});
this->set_parameters({rclcpp::Parameter(pair.first, pair.second)});
}
}

void
ParameterServer::load_parameters(const std::string & key, const std::string & value)
{
if (!parameter_service_) {
throw std::runtime_error("parameter server is not initialized");
}

this->set_parameters({rclcpp::parameter::ParameterVariant(key, value)});
this->set_parameters({rclcpp::Parameter(key, value)});
}

} // namespace controller_parameter_server
50 changes: 20 additions & 30 deletions controller_parameter_server/test/test_parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,24 +38,15 @@ class TestControllerParameterServer : public ::testing::Test
}
};

TEST_F(TestControllerParameterServer, init) {
auto ps = std::make_shared<controller_parameter_server::ParameterServer>();
EXPECT_THROW(ps->load_parameters("key", "value"), std::runtime_error);

ps->init();
EXPECT_NO_THROW(ps->load_parameters("key", "value"));
}

TEST_F(TestControllerParameterServer, init_key_value) {
auto ps = std::make_shared<controller_parameter_server::ParameterServer>();
ps->init();

std::map<std::string, std::string> parameters =
{{
{"test_controller.joints.joint1", "joint1"},
{"test_controller.joints.joint2", "joint2"},
{"test_controller.joints.joint3", "joint3"}
}};
{"test_controller.joints.joint1", "joint1"},
{"test_controller.joints.joint2", "joint2"},
{"test_controller.joints.joint3", "joint3"}
}};

for (auto param : parameters) {
ps->load_parameters(param.first, param.second);
Expand All @@ -81,7 +72,6 @@ TEST_F(TestControllerParameterServer, load_config_file) {
std::string file_path = std::string(yaml_file);

auto ps = std::make_shared<controller_parameter_server::ParameterServer>();
ps->init();
ps->load_parameters(file_path);

auto client_node = std::make_shared<rclcpp::Node>("test_parameter_client_node");
Expand All @@ -105,25 +95,25 @@ TEST_F(TestControllerParameterServer, load_config_file) {

std::vector<std::string> expected_keys =
{{
".controller_name",
".controller_list.0",
".controller_list.1",
".test_joint_controller.joints",
".test_trajectory_controller.joints.0.joint1.name",
".test_trajectory_controller.joints.1",
".test_trajectory_controller.joints.2"
}};
".controller_name",
".controller_list.0",
".controller_list.1",
".test_joint_controller.joints",
".test_trajectory_controller.joints.0.joint1.name",
".test_trajectory_controller.joints.1",
".test_trajectory_controller.joints.2"
}};

std::vector<std::string> expected_values =
{{
"my_controller",
"my_controller1",
"my_controller2",
"my_joint1",
"my_joint1",
"my_joint2",
"my_joint3"
}};
"my_controller",
"my_controller1",
"my_controller2",
"my_joint1",
"my_joint1",
"my_joint2",
"my_joint3"
}};

auto parameter_future = parameters_client->get_parameters(expected_keys);

Expand Down
32 changes: 16 additions & 16 deletions controller_parameter_server/test/test_yaml_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,25 +47,25 @@ TEST_F(TestYamlParser, init) {

std::vector<std::string> expected_keys =
{{
".controller_name",
".controller_list.0",
".controller_list.1",
".test_joint_controller.joints",
".test_trajectory_controller.joints.0.joint1.name",
".test_trajectory_controller.joints.1",
".test_trajectory_controller.joints.2"
}};
".controller_name",
".controller_list.0",
".controller_list.1",
".test_joint_controller.joints",
".test_trajectory_controller.joints.0.joint1.name",
".test_trajectory_controller.joints.1",
".test_trajectory_controller.joints.2"
}};

std::vector<std::string> expected_values =
{{
"my_controller",
"my_controller1",
"my_controller2",
"my_joint1",
"my_joint1",
"my_joint2",
"my_joint3"
}};
"my_controller",
"my_controller1",
"my_controller2",
"my_joint1",
"my_joint1",
"my_joint2",
"my_joint3"
}};

if (expected_keys.size() != expected_values.size()) {
FAIL();
Expand Down

0 comments on commit f15717f

Please sign in to comment.