datetime:2024/07/25 19:07
author:nzb

静态和动态参数使用

静态使用参数,ros加载yaml文件

ROS官方提供了自动加载yaml文件的功能,并且集成到了launch文件里面,只需要使用rosparam标签就能把yaml配置文件加载到ros的参数服务器里面,然后使用nodehandle.getParam()函数就可以方便的使用了。

下面给出关键的使用步骤:

  • 编写yaml文件。注: 避免使用-分割数组,否则容易产生bug,数组使用[],逗号分隔元素。
  • 编写launch文件,加载yaml。核心命令
  • cpp文件中访问yaml。直接使用nodehandle.getParam方法,注意参数的命名空间即可。
  • python文件中访问yaml。直接使用rospy.getParam方法,注意参数的命名空间即可。

static_use_py.py 文件

#!/usr/bin/env python

import rospy


def main():
    rospy.init_node('load_yaml_py')
    node_name = rospy.get_name()
    print('-------------static rospy------------------')
    print('Node name(include ns):', node_name)

    # 获取全局 YAML 参数
    global_car_name = rospy.get_param('/car_name')
    print('global_car_name:', global_car_name)

    # 获取节点内部参数
    inner_car_name = rospy.get_param(node_name + '/car_name')
    print('inner_car_name:', inner_car_name)

    # 获取 double 类型
    car_width = rospy.get_param(node_name + '/DWAParams/car_width', 0.0)
    print('car_width:', car_width)

    # 获取 bool 类型
    is_recover = rospy.get_param(node_name + '/DWAParams/isRecover', False)
    print('isRecover:', is_recover)

    # 获取数组
    origin_pose = rospy.get_param(node_name + '/DWAParams/origin_pose', [])
    print('origin_pose:', origin_pose)

    # 获取嵌套的 YAML
    scan_topic_name = rospy.get_param(
        node_name + '/DWAParams/scan/scan_topic', '')
    print('scan_topic_name:', scan_topic_name)
    print("\n\n\n")
    rospy.spin()


if __name__ == '__main__':
    main()

static_use_cpp.cpp文件

#include <ros/ros.h>

#include <iostream>

int main(int argc, char** argv) {
  ros::init(argc, argv, "load_yaml_cpp");
  ros::NodeHandle nh;

  std::string node_name = ros::this_node::getName();
  std::cout << "--------------static roscpp-----------------" << std::endl;
  std::cout << "Node name(include ns): " << node_name << std::endl;

  std::string global_car_name;
  std::string inner_car_name;
  // 获取全局yaml参数
  nh.getParam("/car_name", global_car_name);
  std::cout << "global_car_name: " << global_car_name << std::endl;
  // 获取node内部参数
  nh.getParam(node_name + "/car_name", inner_car_name);
  std::cout << "inner_car_name: " << inner_car_name << std::endl;
  // 获取double类型
  double car_width;
  nh.getParam(node_name + "/DWAParams/car_width", car_width);
  std::cout << "car_width: " << car_width << std::endl;
  // 获取bool类型
  bool isRecover;
  nh.getParam(node_name + "/DWAParams/isRecover", isRecover);
  std::cout << "isRecover: " << isRecover << std::endl;
  // 获取数组
  std::vector<double> origin_pose;
  nh.getParam(node_name + "/DWAParams/origin_pose", origin_pose);
  std::cout << "origin_pose: ";
  for (auto i : origin_pose) {
    std::cout << i << " ";
  }
  std::cout << std::endl;
  // 获取嵌套的yaml
  std::string scan_topic_name;
  nh.getParam(node_name + "/DWAParams/scan/scan_topic", scan_topic_name);
  std::cout << "scan_topic_name: " << scan_topic_name << "\n\n\n" <<  std::endl;
  ros::spin();
  return 0;
}

备注:yaml中的数组对应cpp标准库中的std::vector,字符串对应为std::string

dwa.yaml文件

car_name: inner_name_BBB
DWAParams:
  # 车辆尺寸
  car_width: 1.5
  car_length: 4.0
  # 算法参数
  v_resolution: 0.2
  w_resolution: 0.2
  # bool 参数设置
  isRecover: true

  # 数组
  origin_pose: [1.0, 1.0, 1.57]
  # 类
  scan:
    scan_topic: /limo/scan
    size: 3
    data: [1, 2, 3]

global_param.yaml文件

car_name: global_car_name_BBB

ROS动态参数服务器

ros动态参数在官方叫做dynamic_reconfigure,这个功能的作用是用于node运行时修改内部参数,区别于静态读取本地yaml文件参数的方式(更常用) 主要用途是在调试机器人时能动态修改机器人参数,而不需要重新编译。 具体操作流程:

  • 1、创建一个cfg文件(python文件),里面定义参数,说白了就像是一个自定义msg。
  • 2、编译功能包,ros会帮我们生成cfg文件的cpp和py文件,以供调用。所以说和自定义msg很像。
  • 3、编写当cfg文件参数修改时的回调函数。
  • 4、使用rqt_reconfigure图形化界面修改cfg文件参数,查看结果。 说实话,着用起来是真的很麻烦,ros门槛是真多。

创建cfg文件

新建功能包依赖于roscpp, rospy, dynamic_reconfigurecfg文件支持,intdoublestringbool,枚举数据类型

mycar.cfg文件

"""
生成动态参数 int,double,bool,string,枚举
实现流程:
    1.导包
    2.创建生成器
    3.向生成器添加若干参数
    4.生成中间文件并退出

"""

# 1.导包
from dynamic_reconfigure.parameter_generator_catkin import *
PACKAGE = "dynamic_static_use_param"

# 2.创建生成器
gen = ParameterGenerator()

# 3.向生成器添加若干参数
#add(name, paramtype, level, description, default=None, min=None, max=None, edit_method="")
gen.add("int_param",int_t,0,"整型参数",50,0,100)
gen.add("double_param",double_t,0,"浮点参数",1.57,0,3.14)
gen.add("string_param",str_t,0,"字符串参数","hello world ")
gen.add("bool_param",bool_t,0,"bool参数",True)                                                                                 

many_enum = gen.enum([gen.const("small",int_t,0,"a small size"),
                gen.const("mediun",int_t,1,"a medium size"),
                gen.const("big",int_t,2,"a big size")
                ],"a car size set")# 枚举类型

gen.add("enum_param",int_t,0,"枚举参数",0,0,2, edit_method=many_enum)

# 4.生成中间文件并退出
exit(gen.generate(PACKAGE,"dynamic_static_use_param","mycar")) #注意最后一个参数必须是cfg文件名

编译cfg文件

mycar.cfg文件其实就是一个py文件,ros编译后生成对应的cpp和py的头文件,分别在devel/includedevel/lib下面。

#cmakelists.txt修改
generate_dynamic_reconfigure_options(
  cfg/mycar.cfg
)

catkin_make编译后,会在devel/include生成对应的cpp头文件,以xxxConfig.h结尾,在devel/lib/python3下面生成python的调用文件,以xxxConfig.py结尾。

dynamic_use_cpp.cpp文件

#include "dynamic_reconfigure/server.h"
#include "dynamic_static_use_param/mycarConfig.h"
#include "ros/ros.h"
/*
   动态参数服务端: 参数被修改时直接打印
   实现流程:
       1.包含头文件
       2.初始化 ros 节点
       3.创建服务器对象
       4.创建回调对象(使用回调函数,打印修改后的参数)
       5.服务器对象调用回调对象
       6.spin()
*/

void cb(dynamic_static_use_param::mycarConfig& config, uint32_t level) {
  ROS_INFO("-------------dynamic roscpp------------------");
  ROS_INFO("动态参数解析数据:%d,%.2f,%d,%s,%d\n\n\n", config.int_param,
           config.double_param, config.bool_param, config.string_param.c_str(),
           config.enum_param);
}

int main(int argc, char* argv[]) {
  setlocale(LC_ALL, "");
  // 2.初始化 ros 节点
  ros::init(argc, argv, "dr");
  // 3.创建服务器对象
  dynamic_reconfigure::Server<dynamic_static_use_param::mycarConfig> server;
  // 4.创建回调对象(使用回调函数,打印修改后的参数)
  dynamic_reconfigure::Server<
      dynamic_static_use_param::mycarConfig>::CallbackType cbType;
  cbType = boost::bind(&cb, _1, _2);
  // 5.服务器对象调用回调对象
  server.setCallback(cbType);
  // 6.spin()
  ros::spin();
  return 0;
}

dynamic_use_py.py文件

#!/usr/bin/env python

import rospy

from dynamic_reconfigure.server import Server
from dynamic_static_use_param.cfg import mycarConfig


def callback(config, level):
    rospy.loginfo("-------------dynamic rospy------------------")
    rospy.loginfo(
        "Reconfigure Request: {int_param}, {double_param},{bool_param},{string_param}, {enum_param}\n\n\n".format(**config))
    return config


if __name__ == "__main__":
    rospy.init_node("dynamic_use_py", anonymous=False)

    srv = Server(mycarConfig, callback)
    rospy.spin()

rqt_reconfigure

使用图形化工具修改参数,回调函数结果。

roscore
# 创建工作空间
cd ~/catkin_ws
catkin_make
source ./devel/setup.bash
# 启动ros节点
roslaunch dynamic_static_use_param bringup.launch
# 使用图形化界面
rosrun rqt_reconfigure rqt_reconfigure

其他文件

bringup.launch文件

<launch>
    <arg name="global_file" default="global_param.yaml" />
    <arg name="inner_file" default="dwa.yaml" />
    <!-- 在node节点外部添加yaml文件,加载到参数服务器 -->
    <rosparam command="load" file="$(find dynamic_static_use_param)/param/$(arg global_file)" />

    <node name="static_use_cpp_node" pkg="dynamic_static_use_param" type="static_use_cpp_node" output="screen" ns="static_use_cpp_ns">
        <!-- 在node节点内部添加yaml参数 -->
        <rosparam command="load" file="$(find dynamic_static_use_param)/param/$(arg inner_file)" />
    </node>

    <node name="static_use_py_node" pkg="dynamic_static_use_param" type="static_use_py.py" output="screen" ns="static_use_py_ns">
        <!-- 在node节点内部添加yaml参数 -->
        <rosparam command="load" file="$(find dynamic_static_use_param)/param/$(arg inner_file)" />
    </node>
    <!-- 动态使用 -->
    <node name="dynamic_use_cpp_node" pkg="dynamic_static_use_param" type="dynamic_use_cpp_node" output="screen" ns="dynamic_use_cpp_ns"/>
    <node name="dynamic_use_py_node" pkg="dynamic_static_use_param" type="dynamic_use_py.py" output="screen" ns="dynamic_use_py_ns"/>
</launch>

CMakeLists.txt文件

cmake_minimum_required(VERSION 3.0.2)
project(dynamic_static_use_param)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
  dynamic_reconfigure
  roscpp
  rospy
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend tag for "message_generation"
##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
##     but can be declared for certainty nonetheless:
##     * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
#   FILES
#   Message1.msg
#   Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
#   DEPENDENCIES
#   std_msgs  # Or other packages containing msgs
# )

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
##   * add "dynamic_reconfigure" to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * uncomment the "generate_dynamic_reconfigure_options" section below
##     and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
generate_dynamic_reconfigure_options(
  cfg/mycar.cfg
)

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES dynamic_static_use_param
#  CATKIN_DEPENDS dynamic_reconfigure roscpp rospy
#  DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
#   src/${PROJECT_NAME}/dynamic_static_use_param.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(static_use_cpp_node src/static_use_cpp.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
target_link_libraries(static_use_cpp_node
  ${catkin_LIBRARIES}
)


add_executable(dynamic_use_cpp_node src/dynamic_use_cpp.cpp)
target_link_libraries(dynamic_use_cpp_node
  ${catkin_LIBRARIES}
)

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMS
  scripts/static_use_py.py
  scripts/dynamic_use_py.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_dynamic_static_use_param.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

results matching ""

    No results matching ""