节点可以使用参数来配置各项操作,这些参数可以说布尔值、整数、字符串等类型。节点在启动时会读取参数。我们将参数单独列出来,而不是写在源文件中,这样做可以方便我们调试,因为在不同的机器人、环境中,我们需要的参数不同。
#include <vector>
#include <string>
#include "rclcpp/rclcpp.hpp"
class LocalizationNode : public rclcpp::Node
{
public:
LocalizationNode()
: Node("localization_node")
{
declare_parameter("number_particles", 200);
declare_parameter("topics", std::vector<std::string>());
declare_parameter("topic_types", std::vector<std::string>());
get_parameter("number_particles", num_particles_);
RCLCPP_INFO_STREAM(get_logger(), "Number of particles: " << num_particles_);
get_parameter("topics", topics_);
get_parameter("topic_types", topic_types_);
if (topics_.size() != topic_types_.size()) {
RCLCPP_ERROR(
get_logger(), "Number of topics (%zu) != number of types (%zu)",
topics_.size(), topic_types_.size());
} else {
RCLCPP_INFO_STREAM(get_logger(), "Number of topics: " << topics_.size());
for (size_t i = 0; i < topics_.size(); i++) {
RCLCPP_INFO_STREAM(get_logger(), "\t" << topics_[i] << "\t - " << topic_types_[i]);
}
}
}
private:
int num_particles_;
std::vector<std::string> topics_;
std::vector<std::string> topic_types_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<LocalizationNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
通过观察上面的代码,我们可以发现
我们可以不使用任何参数启动配置文件,可以观察程序运行后的效果
ros2 run br2_basics param_reader
打印出默认值200,由于topics的默认值为空字符串,所以长度为0
停止程序后,我们使用 --ros-args
和 -p
来设置参数
ros2 run br2_basics param_reader --ros-args -p number_particles:=300 -p topics:='[scan,image]' -p topic_types:='[sensor_msgs/msg/LaserScan,sensor_msgs/msg/Image]'
使用launch文件可以使用两种方法
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
param_reader_cmd = Node(
package='br2_basics',
executable='param_reader',
parameters=[{
'number_particles': 300,
'topics': ['scan', 'image'],
'topic_types': ['sensor_msgs/msg/LaserScan', 'sensor_msgs/msg/Image']
}],
output='screen'
)
ld = LaunchDescription()
ld.add_action(param_reader_cmd)
return ld
在cmake文件中对launch文件进行配置
```cmake
install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME})
在YAML文件中,可以配置参数便于我们进行调试。我们可以通过命令行,使程序能读到配置的参数
localization_node:
ros__parameters:
number_particles: 300
topics: [scan, image]
topic_types: [sensor_msgs/msg/LaserScan, sensor_msgs/msg/Image]
ros2 run br2_basics param_reader --ros-args --params-file install/br2_basics/share/br2_basics/config/params.yaml
使用下列程序,可以读取指定路径下yaml的参数,进行参数的配置
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
pkg_dir = get_package_share_directory('br2_basics')
param_file = os.path.join(pkg_dir, 'config', 'params.yaml')
param_reader_cmd = Node(
package='br2_basics',
executable='param_reader',
parameters=[param_file],
output='screen'
)
ld = LaunchDescription()
ld.add_action(param_reader_cmd)
return ld