<div>I think I may have found the problem. The messages are being sent through the below method in AMCL (confirmed by printing debug messages)</div><div><span class="Apple-style-span" style="font-family: 'Times New Roman'; font-size: medium; "><pre style="word-wrap: break-word; white-space: pre-wrap; ">

void
AmclNode::initialPoseReceivedOld(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
{
  // Support old behavior, where null frame ids were accepted.
  if(msg->header.frame_id == "")
  {
    ROS_WARN("Received initialpose message with header.frame_id == "".  This behavior is deprecated; you should always set the frame_id");
    initialPoseReceived(msg);
  }
}</pre><pre style="word-wrap: break-word; white-space: pre-wrap; ">However, the messages are not being passed on to initialPoseRecieved since their frame is not "".</pre><pre style="word-wrap: break-word; white-space: pre-wrap; ">

Should this code read like this instead...</pre><pre style="word-wrap: break-word; white-space: pre-wrap; ">void</pre><pre style="word-wrap: break-word; white-space: pre-wrap; "><span class="Apple-style-span" style="font-family: 'Times New Roman'; white-space: normal; "><pre style="word-wrap: break-word; white-space: pre-wrap; ">

AmclNode::initialPoseReceivedOld(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
{
  // Support old behavior, where null frame ids were accepted.
  if(msg->header.frame_id == "")
  {
    ROS_WARN("Received initialpose message with header.frame_id == "".  This behavior is deprecated; you should always set the frame_id");</pre><pre style="word-wrap: break-word; white-space: pre-wrap; ">

<span class="Apple-style-span" style="font-family: 'Times New Roman'; white-space: normal; "><pre style="word-wrap: break-word; white-space: pre-wrap; ">  }</pre><pre style="word-wrap: break-word; white-space: pre-wrap; ">

  initialPoseReceived(msg);</pre></span>
}</pre></span></pre><pre style="word-wrap: break-word; white-space: pre-wrap; "><br></pre></span></div><br><div class="gmail_quote">On Fri, Apr 16, 2010 at 6:33 PM, Dan Lazewatsky <span dir="ltr"><<a href="mailto:lazewatskyd@cse.wustl.edu">lazewatskyd@cse.wustl.edu</a>></span> wrote:<br>

<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">


  

<div bgcolor="#ffffff" text="#000000">
Hi Eitan -<br>
I'm inclined to say that this isn't a network issue since lots of other
things work, like streaming video from the robot using image_transport
(and iwconfig shows really good link quality), but I'll try your
suggestions next time I'm in the lab.<br>
<br>
Thanks,<br><font color="#888888">
-Dan</font><div><div></div><div class="h5"><br>
<br>
On 4/16/10 4:12 PM, Eitan Marder-Eppstein wrote:
<blockquote type="cite">Dan,<br>
  <br>
Those are strange problems to have. A hunch I have is that nav_view has
dropped its TCP connection to the robot for one reason or another on
certain topics. This happens to us sometimes when we're switching
between being connected to our robots over ethernet to wireless or when
we lose connectivity to the robot for long periods of time. I'd be
curious about a few things:<br>
  <br>
1) Can you get things to start displaying in nav_view by running the
following command:<br>
     rosrun topic_tools relay [missing_topic_name] [missing_topic_name]<br>
    This will re-advertise the topic and cause nav_view to refresh its
TCP connections.<br>
  <br>
2) Are you sure that the robot can connect to the machine that's
running nav_view? Have you been running rostopic echo on the robot
itself? Or on the local machine?<br>
  <br>
3) If you use rviz, do you see the same kind of problems. If this is a
network issue, I'd expect you to see the same problems, but it'd be
useful to know.<br>
  <br>
Hopefully this helps or we at least find out more about what's going on.<br>
  <br>
Hope all is well,<br>
  <br>
Eitan<br>
  <br>
  <div class="gmail_quote">On Fri, Apr 16, 2010 at 1:54 PM, Dan
Lazewatsky <span dir="ltr"><<a href="mailto:lazewatskyd@cse.wustl.edu" target="_blank">lazewatskyd@cse.wustl.edu</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">Hi
all -<br>
We've been trying to get the nav stack running on one of our robots and<br>
are having some frustrating and not totally reproducible problems. Nav<br>
is setup from config files that I got working on an erratic and have<br>
modified for this robot. When I start up nav_view after getting amcl,<br>
move_base and the like going, most of the time I don't see any laser<br>
scan, inflated obstacles etc. in nav_view and using Set Pose doesn't do<br>
anything. move_base/local_costmap/obstacles is publishing data, and<br>
rxgraph shows it connected to nav_view. When I use Set Pose, I can see<br>
the message getting sent off, but the new pose is not reflected in<br>
nav_view. Sometimes, I'll see the inflated obstacles in nav_view, but<br>
once the map shows up they disappear.<br>
    <br>
Any help would be much appreciated,<br>
-Dan<br>
_______________________________________________<br>
ros-users mailing list<br>
    <a href="mailto:ros-users@code.ros.org" target="_blank">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>
  </blockquote>
  </div>
  <br>
  <pre><fieldset></fieldset>
_______________________________________________
ros-users mailing list
<a href="mailto:ros-users@code.ros.org" target="_blank">ros-users@code.ros.org</a>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a>
  </pre>
</blockquote>
</div></div></div>

<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>