Skip to content

Commit

Permalink
'ros2 param load' fails when double parameter in parameter file is in…
Browse files Browse the repository at this point in the history
… scientific notation

  ros2/ros2cli#834

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Jun 7, 2023
1 parent 012f6b2 commit a970d3b
Show file tree
Hide file tree
Showing 2 changed files with 34 additions and 0 deletions.
1 change: 1 addition & 0 deletions prover_rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ custom_executable(ros2_1400)

#custom_executable(ros2cli_601)
custom_executable(ros2cli_679)
custom_executable(ros2cli_834)

custom_executable(sim_clock_publisher)
custom_executable(intraprocess_pub_sub)
Expand Down
33 changes: 33 additions & 0 deletions prover_rclcpp/src/ros2cli_834.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);

rclcpp::NodeOptions node_options = rclcpp::NodeOptions();
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);

auto node = rclcpp::Node::make_shared("param_test", node_options);
RCLCPP_INFO(node->get_logger(), "/param_test node created...");
// check if already declared
rclcpp::Parameter param;
if (node->has_parameter("test_double")) {
param = node->get_parameter("test_double");
RCLCPP_INFO(node->get_logger(), "test_double param is %f", param.get_value<double>());
} else {
// double type 0.0 initialized
node->declare_parameter("test_double", 0.0);
}
// set parameter type double
node->set_parameter(rclcpp::Parameter("test_double", 3e-06));
param = node->get_parameter("test_double");
RCLCPP_INFO(node->get_logger(), "test_double param is %f", param.get_value<double>());

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
executor.spin();
rclcpp::shutdown();

return 0;
}

0 comments on commit a970d3b

Please sign in to comment.