节点配置
Node标签¶
属性¶
- pkg:要启动的 package名称。
- type:可执行文件名称
- name:可执行文件启动后节点名称
- respawn:进程死掉后是否重启。取值为true或false。默认值为false
- respawn_delay: 重启的时间间隔。单位为秒,默认值为0
- output:将日志输入到什么位置。screen|log。默认值log。
- ns: 名称空间
remap子标签¶
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
<!--
重新映射
1.修改subscriber的topic
from是原来的名称
to修改后的名称 /hello/vel
-->
<!-- <remap from="/hello/turtle1/cmd_vel" to="vel"></remap> -->
<!--
加 / 为全局的
不加 默认会在前面补上 ns
-->
<remap from="/hello/turtle1/cmd_vel" to="/vel"></remap>
<!--
publisher
-->
<remap from="/hello/turtle1/pose" to="/pose"></remap>
</node>
- 可以将topic名称进行映射。
- 加
/
为全局的 - 不加
/
为局部的,会在前面补充 ns名称
内部param子标签¶
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
<param name="key1" value="hello" type="str"></param>
<param name="key2" value="123" type="int"></param>
<param name="key3" value="3.1415926" type="double"></param>
<param name="key4" value="true" type="bool"></param>
<param name="background_r" value="255" type="int"></param>
<param name="background_g" value="100" type="int"></param>
<param name="background_b" value="255" type="int"></param>
</node>
- name: 键
- value: 设置的值
- type: 数据的类型(str|int|double|bool)
- 存储到 master中 名称为 /ns/nodeName/key
全局param参数¶
<param name="key1" value="hello" type="str"></param>
<param name="key2" value="123" type="int"></param>
<param name="key3" value="3.1415926" type="double"></param>
<param name="key4" value="true" type="bool"></param>
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
<param name="background_r" value="255" type="int"></param>
<param name="background_g" value="100" type="int"></param>
<param name="background_b" value="255" type="int"></param>
</node>
内部args属性¶
<launch>
<!--
args 空格分割开
-->
<node pkg="hello_config"
type="args_node.py"
name="args"
output="screen"
args="a=1 b=2 c=3 d=4 e=hello"
></node>
</launch>
全局args属性¶
<launch>
<arg name="hello" default="ok"></arg>
<arg name="bgr" default="255"></arg>
<arg name="bgg" default="100"></arg>
<arg name="bgb" default="255"></arg>
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
<param name="background_r" value="$(arg bgr)" type="int"></param>
<param name="background_g" value="$(arg bgg)" type="int"></param>
<param name="background_b" value="$(arg bgb)" type="int"></param>
</node>
</launch>
- name: 启动launch file的时候,配置的参数中 name名称
- default: 如果启动的时候没有配置这个名称,就给当前这个默认值
- launch file启动参数配置规范:
roslaunch pkg launch文件 name:=value name:=value
$(arg name)
进行访问
include标签¶
include用于引用外部launch文件
<launch>
<!--
launch file的嵌套
include标签
$(find pkg): find命令 pkg具体的包名,找到包的绝对位置
-->
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
</node>
<include file="$(find hello_config)/launch/demo09.launch"></include>
</launch>
$(find pkg)
: find命令 pkg具体的包名,找到包的绝对位置
group分组标签¶
<launch>
<!--
group: node
ns: 配置名称空间
node的全称: /groupNs/nodeNs/nodeName/
-->
<group ns="a">
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
</node>
<node pkg="turtlesim"
type="turtle_teleop_key"
name="teleop_key">
</node>
</group>
<group ns="b">
<node pkg="turtlesim"
type="turtlesim_node"
name="turtle"
respawn="true"
respawn_delay="3"
output="screen"
ns="hello">
</node>
<node pkg="turtlesim"
type="turtle_teleop_key"
name="teleop_key">
</node>
</group>
</launch>