ros2 parameters
c++
#include <rclcpp/rclcpp.hpp>
#include <rcl_interfaces/msg/set_parameters_result.hpp>
#include <string>
#include <vector>
using std::placeholders::_1;
class SimpleParameter: public rclcpp::Node
{
public:
SimpleParameter():Node("simple_parameter")
{
declare_parameter<int>("simple_int_param",28);
declare_parameter<std::string>("simple_str_param","string param");
//在C++中,非静态成员函数需要通过类名限定,并且需要显式传递this指针作为上下文。
param_callback_handle_ = add_on_set_parameters_callback(std::bind(&SimpleParameter::param_callback, this, _1));
}
private:
OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
rcl_interfaces::msg::SetParametersResult param_callback(const std::vector<rclcpp::Parameter> ¶ms)
{
rcl_interfaces::msg::SetParametersResult result;
for (auto &¶m : params)
{
if (param.get_name()=="simple_int_param"&¶m.get_type()==rclcpp::ParameterType::PARAMETER_INTEGER)
{
RCLCPP_INFO_STREAM(get_logger(), "param simple_int_param changed "<<param.as_int());
result.successful=true;
}
if (param.get_name()=="simple_str_param"&¶m.get_type()==rclcpp::ParameterType::PARAMETER_STRING)
{
RCLCPP_INFO_STREAM(get_logger(), "param simple_str_param changed "<< param.as_string()<< std::endl);
result.successful=true;
}
}
return result;
}
};
int main(int argc, char* argv[])
{
rclcpp::init(argc,argv);
auto node = std::make_shared<SimpleParameter>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
调试, 双击tab显示
ros2 run arduinobot_cpp_example simple_parameter --ros-args -p simple_int_param:=37
ros2 param set /simple_parameter simple_str_param "oooooooooooo"
浙公网安备 33010602011771号