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

rclcpp 0.4.0 changes #8

Merged
merged 6 commits into from
Jun 22, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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 @@ -61,10 +61,10 @@ class ControllerInterface : public rclcpp_lifecycle::node_interfaces::LifecycleN
protected:
std::weak_ptr<hardware_interface::RobotHardware> robot_hardware_;
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> lifecycle_node_;
std::shared_ptr<rclcpp::parameter_client::AsyncParametersClient> parameters_client_;
std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client_;

private:
std::shared_ptr<rclcpp::node::Node> parameter_client_node_;
std::shared_ptr<rclcpp::Node> parameter_client_node_;
};

} // namespace controller_interface
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ ControllerInterface::init(
std::bind(&ControllerInterface::on_error, this, std::placeholders::_1));

std::string remote_controller_parameter_server = "controller_parameter_server";
parameters_client_ = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(
parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(
lifecycle_node_->get_node_base_interface(),
lifecycle_node_->get_node_topics_interface(),
lifecycle_node_->get_node_graph_interface(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class ClassLoader;
namespace controller_manager
{

class ControllerManager : public rclcpp::node::Node
class ControllerManager : public rclcpp::Node
{
public:
CONTROLLER_MANAGER_PUBLIC
Expand Down
4 changes: 2 additions & 2 deletions 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 Expand Up @@ -130,7 +130,7 @@ ControllerManager::ControllerManager(
std::shared_ptr<hardware_interface::RobotHardware> hw,
std::shared_ptr<rclcpp::executor::Executor> executor,
const std::string & manager_node_name)
: rclcpp::node::Node(manager_node_name),
: rclcpp::Node(manager_node_name),
hw_(hw),
executor_(executor)
{}
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)
2 changes: 1 addition & 1 deletion controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class TestControllerManager : public ::testing::Test
public:
static void SetUpTestCase()
{
rclcpp::utilities::init(0, nullptr);
rclcpp::init(0, nullptr);
}

void SetUp()
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/test/test_load_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class TestControllerManager : public ::testing::Test
public:
static void SetUpTestCase()
{
rclcpp::utilities::init(0, nullptr);
rclcpp::init(0, nullptr);
}

void SetUp()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
namespace controller_parameter_server
{

class ParameterServer : public rclcpp::node::Node
class ParameterServer : public rclcpp::Node
{
public:
CONTROLLER_PARAMETER_SERVER_PUBLIC
Expand All @@ -35,20 +35,13 @@ class ParameterServer : public rclcpp::node::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::parameter_service::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
21 changes: 3 additions & 18 deletions controller_parameter_server/src/parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,23 +22,12 @@ namespace controller_parameter_server
{

ParameterServer::ParameterServer()
: rclcpp::node::Node("controller_parameter_server")
: rclcpp::Node("controller_parameter_server")
{}

void
ParameterServer::init()
{
parameter_service_ =
std::make_shared<rclcpp::parameter_service::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
54 changes: 22 additions & 32 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,12 +72,11 @@ 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::Node>("test_parameter_client_node");
auto client_node = std::make_shared<rclcpp::Node>("test_parameter_client_node");
auto parameters_client =
std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(client_node, ps->get_name());
std::make_shared<rclcpp::AsyncParametersClient>(client_node, ps->get_name());

rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(ps);
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