[ros-users] gmapping and navigation stack

Eric Perko wisesage5001 at gmail.com
Fri Jan 28 21:11:56 UTC 2011


On Fri, Jan 28, 2011 at 3:58 PM, airthimble <joseph.st.amand at mines.sdsmt.edu
> wrote:

>
> Hello there,
>
> I am trying to get the navigation stack and gmapping to work together, I
> get
> a couple of errors that I have spent many hours on that I cannot seem to
> solve. I have not used ros extensively but have been able to drive the
> robot
> around using my computer and create maps with the gmapping package.
>
> This is the first error:
> [ERROR] [1296247552.958952582]: Client [/move_base] wants topic
> /initialpose
> to have datatype/md5sum
> [sensor_msgs/PointCloud/d8e9c3f5afbdd8a130fd1d2763945fca], but our version
> has
> [geometry_msgs/PoseWithCovarianceStamped/953b798c0f514ff060a53a3498ce6246].
> Dropping connection.
>

Pretty sure this is due to rviz publishing a
geometry_msgs/PoseWithCovarianceStamped on the /initialpose topic, while
move_base is subscribing to that topic and expecting a
sensor_msgs/PointCloud. What were you trying to achieve by feeding that in
as an observation source to your costmaps?

- Eric


>
> The second error is:
> [ WARN] [1296247614.045447300]: The origin for the sensor at (0.11, -0.01,
> 0.13) is out of map bounds. So, the costmap cannot raytrace for it.
>
> I am able to see gmapping start creating a map in rviz, however, when I
> give
> rviz a navigation goal the robot rotates a few degrees and the map bounds
> error appears.
>
> I have attached many of the files that I use for you to view.
>
> Any suggestions on how to fix this would be greatly appreciated.
>
> Thanks!
> http://ros-users.122217.n3.nabble.com/file/n2368030/move_base.launch
> move_base.launch
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/aten_configuration.launch
> aten_configuration.launch
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/local_costmap_params.yaml
> local_costmap_params.yaml
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/global_costmap_params.yaml
> global_costmap_params.yaml
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/costmap_common_params.yaml
> costmap_common_params.yaml
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/base_local_planner_params.yaml
> base_local_planner_params.yaml
> http://ros-users.122217.n3.nabble.com/file/n2368030/frames.pdf frames.pdf
>
>
>
> http://ros-users.122217.n3.nabble.com/file/n2368030/Screenshot.png
> Screenshot.png
> http://ros-users.122217.n3.nabble.com/file/n2368030/Screenshot-2.png
> Screenshot-2.png
>
>
>
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/gmapping-and-navigation-stack-tp2368030p2368030.html
> Sent from the ROS-Users mailing list archive at Nabble.com.
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20110128/dcc0734b/attachment-0005.html>


More information about the ros-users mailing list