赞
踩
ros单个工程的运行可以使用rosrun,但是做项目不可能只有一个或几个工程,当需要大量的工程配合运行时launch就应运而生了
关于launch的说明可以参考ROS入门之——浅谈launch
这里重点说明几点:
launch文件示例:
<launch>
<param name="version" value="1.0.1"/>
<arg name="arg1" default="0.01"/>
<node pkg="can_pkg" name="car_control_node" type="car_control_node"/>
<node pkg="can_pkg" name="radar_parsing_node" type="radar_parsing_node" output="screen"/>
<node pkg="aeb_pkg" name="aeb" type="aeb" output="log"/>
<node pkg="ssd_pkg" name="ssd" type="ssd.py" >
<param name="rosRate" type="double" value="$(arg arg1)"/>
</node>
<group ns="gains">
<param name="P" type="double" value="1.0" />
<param name="I" type="double" value="2.0" />
<param name="D" type="double" value="3.0" />
</group>
</launch>
roslaunch ssd_pkg merge.launch arg1:=0.15
内部参数使用~ :比如rosRate为ssd_pkg的内部参数,其他包不能使用
全局参数加/ :version为全局参数,所有包可以加载
当然内部参数可以使用全路径方式指定:/ssd_pkg/rosRate
ros::init(argc, argv, "path_show"); ros::NodeHandle n("~"); //默认获取内部参数 double rate; std_msgs::String version; //参数的获取 n.getParam("/version", version); // 全局参数,加/ n.getParam("rosRate", rate); //或 ros::param::get("/ssd_pkg/rosRate", rate); // 获取不到指定的param,可以给一个默认值 n.param("rosRate", rate, 1.5); //除了获取参数外还能设置,检查,删除参数 ros::param::set("rosRate", 1.5); n.setParam("rosRate",1.5); bool has = ros::param::has("rosRate"); has = n.hasParam("rosRate"); bool del= n.deleteParam("rosRate"); del= ros::param::del("rosRate");
if rospy.has_param('gains'):
gains = rospy.get_param('gains')
p, i, d = gains['P'], gains['I'], gains['D']
YAML(发音 /ˈjæməl/)是一个可读性高,用来表达数据序列化的格式,
其命名来历很有意思:
其语法可以参考YAML文件简介
这里拿个小例子说明:
注意
1.yaml使用空格设置层级,多少个空格没关系,保持一致即可,不能使用table
2. -开头组成列表(当然也可以使用[]),字典使用{}加键值对
3. 类型会自动识别字符串和数字,如果要指定为字符串需要用双引号
4. 重点说明:yaml缩进不能使用table
merge_area: # 对象
car: {left: 0, top: 0.5, right: 1, bottom: 1.25} # 字典的使用
bus: {left: 0.125, top: 0.5, right: 0.875, bottom: 1.25}
person: {left: -0.25, top: 0.75, right: 1.25, bottom: 1.25}
image_path: /home/fly/catkin_ws/image/ # 可以不用带引号
pi: 3.14 # 默认为数字,若要定义为字符串需要加双引号
PID: # 列表的使用,等同于 [{'P': 1.0}, {'I': 2.0}, {'D': 3.0}]
- P: 1.0
- I: 2.0
- D: 3.0
找到test_pkg同级目录的config.yaml然后加载它
<launch>
<node pkg="test_pkg" name="test" type="test.py" respawn="true" output="screen">
<rosparam file="$(find test_pkg)../config.yaml" command="load"/>
</node>
</launch>
获取配置的属性值
#!/usr/bin/env python3 #coding=utf-8 import rospy def get_param(): print("start test package .... ") area = rospy.get_param('~merge_area') image_path = rospy.get_param('~image_path') pid = rospy.get_param('~PID') print(area) print(image_path) print(pid) if __name__ == '__main__': try: rospy.init_node('test', anonymous=True) get_param() except rospy.ROSInterruptException: print('ROSInterruptException') pass
打印输出
start test package ....
{'person': {'top': 0.75, 'right': 1.25, 'bottom': 1.25, 'left': -0.25}, 'bus': {'top': 0.5, 'right': 0.875, 'left': 0.125, 'bottom': 1.25}, 'car': {'top': 0.5, 'left': 0, 'right': 1, 'bottom': 1.25}}
/home/fly/catkin_ws/image/
[{'P': 1.0}, {'I': 2.0}, {'D': 3.0}]
利用ROS自带的XmlRpc::XmlRpcValue实现一维数组或者二位数组等类似json数据的读取
yaml文件
# yaml文件
scanners:
- {pub_topic: "scan_head", frame_id: "laser_scanner_link_head",server_ip: "192.168.167.100",server_port: 2111}
- {pub_topic: "scan_middle",frame_id: "laser_scanner_link_middle",server_ip: "192.168.167.101",server_port: 2111}
- {pub_topic: "scan_tail",frame_id: "laser_scanner_link_tail",server_ip: "192.168.167.102",server_port: 2111}
merge_area:
car: {left: 0, top: 0.5, right: 1.0, bottom: 1.25}
bus: {left: 0.125, top: 0.5, right: 0.875, bottom: 1.25}
person: {left: -0.25, top: 0.75, right: 1.25, bottom: 1.25}
num_list: [37.783, 1.414, 3.14, 0.618]
C++读取代码
#include <ros/ros.h> #include <std_msgs/String.h> #include <string> using namespace std; int main(int argc, char **argv) { ros::init(argc, argv, "path_show"); ros::NodeHandle nh("~"); //字典数组的解析 XmlRpc::XmlRpcValue params; nh.getParam("scanners", params); for(size_t i = 0; i<params.size(); ++i) { const std::string& server_ip = params[i]["server_ip"]; const std::string& frame_id = params[i]["frame_id"]; const std::string& pub_topic = params[i]["pub_topic"]; const int& server_port = params[i]["server_port"]; printf("ip:%s, id:%s, topic:%s, port:%d \r\n", server_ip.c_str(), frame_id.c_str(), pub_topic.c_str(), server_port); } //数组写入向量 XmlRpc::XmlRpcValue nums; nh.getParam("num_list", nums); std::vector<double> num_list; for (size_t i = 0; i < nums.size(); ++i) { XmlRpc::XmlRpcValue tmp_value = nums[i]; if(tmp_value.getType() == XmlRpc::XmlRpcValue::TypeDouble) num_list.push_back(double(tmp_value)); printf("get one num: %f\r\n", double(tmp_value)); } //字典读取,注意类型对应 XmlRpc::XmlRpcValue area; nh.getParam("merge_area", area); XmlRpc::XmlRpcValue car= area["car"]; printf("car_area = top: %f, left: %d, bottom: %f, right: %f\r\n", double(car["top"]), int(car["left"]), double(car["bottom"]), double(car["right"])); }
注意类型的转换,需要注意一一对应,如果不对应,就会报错,(如:int不能使用double强转)
报错信息:terminate called after throwing an instance of ‘XmlRpc::XmlRpcException’
输出信息
ip:192.168.167.100, id:laser_scanner_link_head, topic:scan_head, port:2111
ip:192.168.167.101, id:laser_scanner_link_middle, topic:scan_middle, port:2111
ip:192.168.167.102, id:laser_scanner_link_tail, topic:scan_tail, port:2111
get one num: 37.783000
get one num: 1.414000
get one num: 3.140000
get one num: 0.618000
car_area = top: 0.500000, left: 0, bottom: 1.250000, right: 1.000000
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。