ROS中topic重映射理解及验证(remap标签)

2 篇文章 3 订阅
1 篇文章 0 订阅

在这里插入图片描述

先附上个人总结:

  • remap在node标签<node> ... </node>之外的作用域是其之后的所有节点;

    <node> ...  </node>  <!-- 不受remap影响 -->
    <remap />
    <node> ...  </node>  <!-- 受remap影响 -->
    
  • remap在node标签<node> ... </node>之间的作用域是当前节点;

    <node> ...  </node>  <!-- 不受remap影响 -->
    <node>
      <remap />
    </node>  <!-- 受remap影响 -->
    <node> ...  </node>  <!-- 不受remap影响 -->
    
  • 如果launch之间没有调用,某一个launch中的remap不会在其它launch中生效;

  • 如果launch间存在调用,某一个被调用的launch中的remap不会在其它launch中生效;

    <!-- 被调用.launch -->
    <launch>
      <node> ... </node> <!-- 不受remap影响 -->
      <remap />
      <node> ... </node> <!-- 受remap影响 -->
    </launch>
    
    <!-- 集成.launch -->
    <launch>
      <include file="$(find xxx)被调用.launch"/>
      <node> ... </node>  <!-- 不受<被调用.launch>中的remap影响 -->
      <include file="$(find xxx)其它.launch"/>  <!-- 不受<被调用.launch>中的remap影响 -->
    </launch>
    ```xml
    
    
  • 如果launch间存在调用,集成launch中的remap按照launch文件中node的顺序考虑remap的作用域;

    <launch>
      <include file="$(find xxx)xxx1.launch"/> <!-- 不受remap影响 -->
      <remap />
      <node> ... </node>  <!-- 受remap影响 -->
      <include file="$(find xxx)xxx2.launch"/>  <!-- 受remap影响 -->
    </launch>
    
  • <include> ... </include>标签内插入remap不起任何作用,不会像arg那样发生传递。

    <include file="$(find xxx)xxx.launch">
      <remap />  <!-- 不起任何作用 -->
    </include>
    

remap-wiki中的解释

Remapping allows you to “trick” a ROS node so that when it thinks it is subscribing to or publishing to /some_topic it is actually subscribing to or publishing to /some_other_topic, for instance.
其它节点已经订阅或者发布的topic(姑且称为target_topic)满足不了我的需求,通过瞒天过海、易容术(remap),使我以为我发布或者订阅到了期望的(node中预定义好的)topic(姑且称为source_topic),但是实际却不是(虽然化妆或者整容了,但是还是原来的那个)。所以如果remap成功,只能看到target_topic,看不到source_topic

  • 官方表达
    from="original-name"
    Remapped topic: name of the ROS topic that you are remapping FROM.
    to="new-name"
    Target name: name of the ROS topic that you are pointing the from topic TO.
    this means that if you remap FROM topic “A” TO topic “B”, then whenever a node thinks it is subscribing to topic “A”, it is actually subscribing to topic “B”, so anyone publishing to topic “B” will end up getting their message to this node!
  • 简单例子
    For example, you are given a node that says it subscribes to the “chatter” topic, but you only have a node that publishes to the “hello” topic. They are the same type, and you want to pipe your “hello” topic into the new node which wants “chatter”. You can do this with this remap: <remap from="chatter" to="hello"/>
    Again, this example is from the perspective of the receiving node which subscribes to the topic. So, when this node subscribes to topic “chatter” in its source code, it is remapped to actually subscribe to “hello”, so that it ends up receiving any messages published by other ROS nodes to “hello”.

代码验证

通过实际代码案例验证

  • 用于实验的node及lauch文件

    • 三个node:

      • node talker发布topic/chatter
      • node listener_1希望接收topic /chatter
      • node listener_2希望接收topic /good/chatter
    • 几个launch

      • talker.launch

        <launch>
          <node name="talker" pkg="beginner_tutorials" type="talker" output="screen" />
        </launch>
        
      • listener_1.launch

          <launch>
            <node name="listener_1" pkg="beginner_tutorials" type="listener_1" output="screen" />
          </launch>
        
      • listener_2.launch

          <launch>
            <node name="listener_2" pkg="beginner_tutorials" type="listener_2" output="screen" />
          </launch>
        
      • listener_1_2.launch:node1调用在前,node2调用在后

          <launch>
          	<include file="$(find beginner_tutorials)/launch/listener_1.launch">
          	<include file="$(find beginner_tutorials)/launch/listener_2.launch">
          </launch>
        

      现通过在launch文件中插入remap,以实现节点通讯。remap的插入位置文字定义如下:

      • node标签内插入

        <node>
          <remap /> 
        </node>
        
      • node上插入

        <remap />
        <node>
        </node>
        
      • node下插入

        <node>
        </node>
        <remap />
        

    实验结果:

    序号remap位置remap方向listener_1通讯结果listener_2通讯结果结论
    1不插入<remap from="/good/chatter" to="/chatter"/>成功失败-
    2listener_2.launch,node标签内插入<remap from="/good/chatter" to="/chatter"/>成功成功-
    3listener_2.launch,node上插入<remap from="/good/chatter" to="/chatter"/>成功成功-
    4listener_2.launch,node下插入<remap from="/good/chatter" to="/chatter"/>成功失败node标签之外的作用域是其之后的节点,所以remap并生效,node listener_2还是订阅/good/chatter
    5talker.launch,node标签内插入<remap from="/chatter" to="/good/chatter"/>失败成功-
    6talker.launch,node上插入<remap from="/chatter" to="/good/chatter"/>失败成功node标签之外的作用域是其之后的节点,所以remap生效
    7talker.launch,node下插入<remap from="/chatter" to="/good/chatter"/>失败失败node标签之外的作用域是其之后的节点,但是此处remap之后没有节点
    8listener_1.launch,node标签内插入<remap from="/good/chatter" to="/chatter"/>成功失败在node中的作用域是当前节点,所以node listener_2还是订阅/good/chatter
    9listener_1.launch,node上插入<remap from="/good/chatter" to="/chatter"/>成功失败如果launch之间没有调用,某一个launch中的remap不会在其它launch中生效,所以node listener_2还是订阅/good/chatter
    10listener_1.launch,node下插入<remap from="/good/chatter" to="/chatter"/>成功失败如果launch之间没有调用,某一个launch中的remap不会在其它launch中生效,所以node listener_2还是订阅/good/chatter
    11listener_1.launch,node标签内插入<remap from="/chatter" to="/good/chatter"/>失败失败两个listener都订阅/good/chatter,但talker发布/chatter
    12listener_1.launch,node上插入<remap from="/chatter" to="/good/chatter"/>失败失败两个listener都订阅/good/chatter,但talker发布/chatter
    13listener_1.launch,node下插入<remap from="/chatter" to="/good/chatter"/>成功失败node标签之外的作用域是其之后的节点,所以remap并生效,node listener_1还是订阅/chatter
    14listener_1_2.launch,listener_1include标签内插入<remap from="/chatter" to="/good/chatter"/>成功失败include标签内插入remap不起任何作用,不会像arg那样发生传递,所以node listener_1还是订阅/chatter
    15listener_1_2.launch,listener_2include标签内插入<remap from="/good/chatter" to="/chatter"/>成功失败include标签内插入remap不起任何作用,不会像arg那样发生传递,所以node listener_2还是订阅/good/chatter
    16listener_1_2.launch,listener_1上插入<remap from="/chatter" to="/good/chatter"/>失败失败如果launch存在调用,按照launch文件中node的顺序考虑remap的作用域,所以两个listener都订阅/good/chatter,但talker发布/chatter
    17listener_1_2.launch,listener_1listener_2之间插入<remap from="/good/chatter" to="/chatter"/>成功成功如果launch存在调用,按照launch文件中node的顺序考虑remap的作用域 & node标签之外的作用域是其之后的节点,所以node listener_2订阅了/chatter

参考链接:

  • 10
    点赞
  • 34
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

lyh458

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值