Travis,<br><br>If you run the normal navigation stack at the same time
as assisted teleop, you're correct in that each will maintain its own
occupancy grid. At some point, I want to re-implement the navigation
stack using nodelets which would allow for things like the costmap to
have a ROS interface that could be used by multiple nodes/nodelets, but
that's for the future.<br>

<br>As far as your remapping call goes, you're almost there, but you
have to be explicit about using the private namespace. This is a bit
unintuitive because using the "param" tag within a "node" tag
automatically puts things in the private namespace, but the "remap" tag
does not. I guess this is so that parameter remappings and topic
remappings are consistent, but its admittedly kind of a pain. So, if
you change your remaps to look like the ones I've pasted below, I think
things should work:<br>

<br><remap from="~/costmap" to="move_base_node/local_costmap" /><br><div class="im"><remap from="~/planner" to="move_base_node/TrajectoryPlannerROS" /></div><br>Hope this helps,<br>
<br>Eitan<br><br><div class="gmail_quote">On Tue, Jul 20, 2010 at 3:29 PM, Travis Deyle <span dir="ltr"><<a href="mailto:beambot@gmail.com">beambot@gmail.com</a>></span> wrote:<br><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">
Hello,<br><br>I'm trying to figure out a slick way to load the 2d_costmap from /move_base_node/local_costmap (loaded by 2dnav) into my own Costmap2DROS (in assisted_teleop's "costmap").  I imagine there is a slick solution using remap, but it alludes me:<br>

<br><launch><br>  <!-- Launch the assisted Teleop with own yaml --><br>  <node pkg="assisted_teleop" name="assisted_teleop"<br>        type="assisted_teleop" respawn="false" output="screen"><br>

    <remap from="cmd_vel" to="cmd_vel_tmp" /><br>    <remap from="costmap" to="/move_base_node/local_costmap" /><br>    <remap from="planner" to="/move_base_node/TrajectoryPlannerROS" /><br>

  </node><br></launch><br><br>One solution that already works is to generate my own costmap / planner using my own YAML files (vis-a-via the method used by assisted_teleop).  However, this seems to be a duplication of effort (maintaining a costmap with different parameters when the 2dnav costmap is already running and tuned).  Suggestions?  <br>
<font color="#888888">
<br>~Travis Deyle<br>
PhD student @ Georgia Tech's Healthcare Robotics Lab<br>
<br>
</font><br>_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
<br></blockquote></div><br>