-
Notifications
You must be signed in to change notification settings - Fork 522
Closed
Labels
bugSomething isn't workingSomething isn't working
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 18.04
- Installation type:
- from source
- Version or commit hash:
- Dashing, master
- DDS implementation:
- Fast-RTPS
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
Parameter Service code
#include <chrono>
#include <iostream>
#include <memory>
#include <vector>
#include <rclcpp/rclcpp.hpp>
int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor executor;
auto node = std::make_shared<rclcpp::Node>("param_test_server_node");
auto test_param = "test_param";
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.read_only = false;
node->declare_parameter(test_param, rclcpp::ParameterValue(10), descriptor);
executor.add_node(node);
node->set_on_parameters_set_callback([&](const std::vector<rclcpp::Parameter> & parameters) {
rcl_interfaces::msg::SetParametersResult result;
std::cout << "set_parameter callback is called" << std::endl;
result.successful = true;
for (const auto & parameter : parameters) {
if (parameter.get_name() == test_param)
{
std::cout << test_param << " " << parameter.value_to_string() << std::endl;
}
}
return result;
});
executor.spin();
rclcpp::shutdown();
return 0;
}Parameter Client Code
#include <chrono>
#include <iostream>
#include <memory>
#include <vector>
#include <rclcpp/rclcpp.hpp>
int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
auto remote_node = "/param_test_server_node";
auto test_param = "test_param";
auto node = std::make_shared<rclcpp::Node>("param_test_client");
auto parameters_client =
std::make_shared<rclcpp::SyncParametersClient>(node, remote_node);
std::this_thread::sleep_for(std::chrono::seconds(1));
while (!parameters_client->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "interrupted, exit!");
rclcpp::shutdown();
return 0;
}
RCLCPP_INFO(node->get_logger(), "wait for service");
}
std::vector<std::string> params;
params.emplace_back(test_param);
auto results = parameters_client->get_parameter_types(params);
for (auto &result : results) {
RCLCPP_INFO(node->get_logger(), "param_type: %d", result);
}
rclcpp::shutdown();
return 0;
}
Expected behavior
[INFO] [param_test_client]: param_type: 2
Actual behavior
Nothing
Reactions are currently unavailable
Metadata
Metadata
Assignees
Labels
bugSomething isn't workingSomething isn't working