Mike,<br><br><div class="gmail_quote">On Tue, Jun 8, 2010 at 7:36 AM, Mike Purvis <span dir="ltr"><<a href="mailto:mpurvis@clearpathrobotics.com">mpurvis@clearpathrobotics.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;">
<div class="im"><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0px 0px 0px 0.8ex; padding-left: 1ex;">

If you're doing a lot of multi-robot navigation and you want the robot's to be aware of each other's positions, you'll probably need a map frame. You don't necessarily need to run a map_server, but you will need to have your localization source, whether that be GPS, camera-based localization, or other, publish a transform from the map frame to the odom (or if you don't have odom, base_link) frame of your robot. In the case where you don't have a map_server... you'd still set the "static_map" parameter on the global_costmap to be false.</blockquote>


<div class="gmail_quote"><br></div></div><div class="gmail_quote">This is very helpful, thanks.</div><div class="gmail_quote"><br></div><div class="gmail_quote"><div class="im"><br><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">


<div class="gmail_quote"><div>With the parameters that you posted, you should no longer receive this error. Can you take a look at the parameters you have set with "rosparam dump" to make sure that the parameters for the global_costmap are being set correctly? They should fall under the move_base_node/global_costmap/ namespace.</div>


</div></blockquote><div><br></div></div><div>Okay, yes, I've played with the namespaces, and I believe all of the pieces are now seeing the proper parameters. Thanks for the tip about rosparam dump.</div><div><br></div>
<div>

I have a few remaining questions about global_costmap and local_costmap. I have the navigation stack talking to my simulator, but when I send a goal, I get the following output:</div><div><br></div><div><div>[ WARN] 1276006631.337854000: The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.</div>


<div>[ WARN] 1276006631.425825000: The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.</div><div>[ WARN] 1276006631.704455000: The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?</div>


<div>[ WARN] 1276006631.825804000: The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.</div><div>[ WARN] 1276006631.904408000: The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?</div>


<div>[ERROR] 1276006631.949307000: Aborting because a valid plan could not be found. Even after executing all recovery behaviors</div></div></div></blockquote><div><br>You shouldn't be receiving the "robot's start position is off the global costamp" error if you have the "rolling_window" parameter set to true. It should automatically center the robot in a costmap that has an origin appropriate for the robot's position. It may take an update cycle to do this, but it should work. Can you try setting the publish_frequency parameter to something non zero on your global_costmap and viewing it in rviz? You should see the costmap with its associated obstacles and the robot footprint in the center of it. You can find information on using rviz with the navigation stack here: <a href="http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack">http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack</a><br>
 </div><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><div class="gmail_quote"><div><br></div><div>Now, I'm using raw UTM coordinates for my position, so the numbers are large. My odometry messages (and corresponding transforms) look like so:</div>


<div><br></div><div><div>header: </div><div>  seq: 4657</div><div>  stamp: 1276006871180577039</div><div>  frame_id: odom</div><div>child_frame_id: base_link</div><div>pose: </div><div>  pose: </div><div>    position: </div>


<div>      x: 596506.594977</div><div>      y: 4956355.18823</div><div>      z: 0.0</div><div>    orientation: </div><div>      x: 0.0</div><div>      y: 0.0</div><div>      z: 0.922148700667</div><div>      w: 0.386835590217</div>


<div>  covariance: [0.0 ...</div></div><div><br></div><div>And my goal, accordingly, was sent like so:</div><div><br></div><div><div>rostopic pub /clearpath/robots/0/move_base_simple/goal geometry_msgs/PoseStamped '{ header: { frame_id: "odom" }, pose: { position: { x: 596505, y: 4956355 }, orientation: { x: 0, y: 0, z: 0.62, w: 0.78 } } }'</div>


<div>publishing and latching message. Press ctrl-C to terminate</div></div><div><br></div><div>Now, I've tried to center the global costmap over this region, like so:</div><div><br></div><div><div class="im"><div>global_costmap:</div>


<div>  global_frame: odom</div><div>  robot_base_frame: base_link</div><div>  update_frequency: 5.0</div><div>  static_map: false</div><div>  rolling_window: true</div></div><div>  width: 100</div><div>  height: 100</div>
<div>
  origin_x: 596500</div>
<div>  origin_y: 4956350</div><div>  map_type: costmap</div></div><div><br></div><div>Is this a correct approach? Alternatively, I could put a local origin in my odometry and tf broadcasters. Would that be better? Or is there something else entirely?</div>
</div></blockquote><div><br>Setting the origin for the costmap is a reasonable thing to do when rolling_window is not set, but having the rolling_window parameter set to true will actually override your original origin setting every update cycle to center the robot in the costmap. I'm surprised that setting the origin makes things work for you, but leaving it at (0, 0) causes things to break. Looking at what is going on in rviz may clear things up, however.<br>
<br>Hope this helps,<br><br>Eitan<br> <br></div><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><div class="gmail_quote">

<div><br></div><div>Thanks again.</div></div>
</blockquote></div><br>