You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
cmake_minimum_required(VERSION 3.8)
project(my_test_pkg)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES"Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependenciesfind_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in# further dependencies manually.find_package(rclcpp REQUIRED)
add_executable(my_node src/my_node.cpp)
target_include_directories(my_node PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_compile_features(my_node PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17
ament_target_dependencies(my_node rclcpp)
install(TARGETS my_node
DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights# comment the line when a copyright and license is added to all source files set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)# comment the line when this package is in a git repo and when# a copyright and license is added to all source files set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
Update source my_node.cpp
#include<cstdio>
#include"rclcpp/rclcpp.hpp"staticconstexprconstuint8_t EXAMPLE_ARR[8]{ 0x00, 0x13, 0xA2, 0x00, 0x41, 0x5C, 0x61, 0x86 };
intmain(int argc, char ** argv)
{
rclcpp::init(argc, argv);
printf("hello world my_test_pkg package\n");
auto node = rclcpp::Node::make_shared("my_node");
auto param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(node);
auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
param_desc.description = "XBee Due address";
auto dueAddrParm = node->declare_parameter(
"byte_arr_param",
std::vector<uint8_t>(EXAMPLE_ARR,
EXAMPLE_ARR + sizeof(EXAMPLE_ARR) / sizeof(EXAMPLE_ARR[0])),
param_desc);
auto p = node->get_parameter("byte_arr_param");
RCLCPP_INFO_STREAM(node->get_logger(), p.get_name() << ":=" << p.value_to_string() << " (initial)");
rclcpp::spin(node);
rclcpp::shutdown();
return0;
}
compile and source workspace then run the node.
colcon build &&source install/setup.bash
ros2 run my_test_pkg my_node
Dump the parameters
ros2 param dump /my_node > ./params.yaml
Restart the node with the parameters from the dump
ros2 run my_test_pkg my_node --ros-args --params-file ./params.yaml
Expected behavior
Node spins as previously or displays different param value if changed in params.yaml before execution, e.g.:
$ ros2 run my_test_pkg my_node --ros-args --params-file ./params.yaml
hello world my_test_pkg package
terminate called after throwing an instance of 'rclcpp::exceptions::InvalidParameterTypeException'what(): parameter 'byte_arr_param' has invalid type: Wrong parameter type, parameter {byte_arr_param} is of type {byte_array}, setting it to {string_array} is not allowed.
[ros2run]: Aborted
Additional information
The text was updated successfully, but these errors were encountered:
Bug report
Required Info:
Steps to reproduce issue
package.xml
CMakeLists.txt
my_node.cpp
ros2 param dump /my_node > ./params.yaml
Expected behavior
Node spins as previously or displays different param value if changed in
params.yaml
before execution, e.g.:Actual behavior
An exception is thrown:
Additional information
The text was updated successfully, but these errors were encountered: