Hi Everyone,
I just ran into a very nasty bug when running Move_base on a armhf (ArmHardFloatPort) ARM CPU(armv7l). I am running the latest Fuerte code on Ubuntu 12.04.
The only things I am running are roscore, move_base, and map_server. The problem happens when I send move_base a blank map. Move_base prints "Still waiting on map..." and then when I send it a map through the map_server, it immediately crashes with the following error "Program received signal SIGBUS, Bus error".
The back-trace from GDB of move_base is as follows:
[ INFO] [1358269351.739542577]: Still waiting on map...
[ INFO] [1358269352.739512061]: Still waiting on map...
Program received signal SIGBUS, Bus error.
0xb6ee27fa in ros::SubscriptionCallbackHelperT> const> const&, void>::deserialize(ros::SubscriptionCallbackHelperDeserializeParams const&) () from /home/name/ros/navigation/costmap_2d/lib/libcostmap_2d.so
(gdb) bt
#0 0xb6ee27fa in ros::SubscriptionCallbackHelperT> const> const&, void>::deserialize(ros::SubscriptionCallbackHelperDeserializeParams const&) () from /home/name/ros/navigation/costmap_2d/lib/libcostmap_2d.so
#1 0xb6dc2d68 in ros::MessageDeserializer::deserialize() () from /opt/ros/fuerte/lib/libroscpp.so
#2 0xb6dbe2f4 in ros::SubscriptionQueue::call() () from /opt/ros/fuerte/lib/libroscpp.so
#3 0xb6d6b4e6 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/fuerte/lib/libroscpp.so
#4 0xb6d6b0ac in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/fuerte/lib/libroscpp.so
#5 0xb6da4a5a in ros::spinOnce() () from /opt/ros/fuerte/lib/libroscpp.so
#6 0xb6ebbbda in costmap_2d::Costmap2DROS::Costmap2DROS(std::string, tf::TransformListener&) ()
from /home/name/ros/navigation/costmap_2d/lib/libcostmap_2d.so
#7 0x00000000 in ?? ()
(gdb)
The error printed out from the kernel "dmesg" is as follows:
Alignment trap: not handling instruction ed967b05 at []
Unhandled fault: alignment exception (0x011) at 0xb14c202f
The problem seems to be directly related to the fact that it is a armhf system. X86 systems seem to take care of alignment problems a lot better then ARM.
Based on the "/proc/cpu/alignment" file it is set to "2" which means fixup. If I send this file a "3" it will warn me of the alignment problems. Doing this and running other ROS nodes, I know it is fixing most of the alignment bugs that ROS has in it, but it is unable to fix this one for some reason.
Does anyone have any suggestions on how to fix this bug?
Thank you
---------------------------------------
**UPDATE**
---------------------------------------
To fix this problem, I had to edit the CMakeLists.txt file in the costmap_2d package. I added "set(ROS_BUILD_TYPE debug)" and recompiled it. Move_base now got to the point of asking for the "tf" from /base_link to /map.
Unfortunately, after I sent a static transform with the static_transform_publisher it proceeded with a similar but different bus error.
Here is the GDB back trace of the new error:
[ WARN] [1358354683.016454689]: Waiting on transform from /base_link to /map to become available before running costmap, tf error:
[ WARN] [1358354688.094640723]: Waiting on transform from /base_link to /map to become available before running costmap, tf error:
Program received signal SIGBUS, Bus error.
[Switching to Thread 0xb2aff3f0 (LWP 9943)]
0xb6cd2116 in read (v=@0xb34007d8: 0, stream=...) at /opt/ros/fuerte/include/ros/serialization.h:201
warning: Source file is more recent than executable.
201 ROS_CREATE_SIMPLE_SERIALIZER(double);
(gdb) bt
#0 0xb6cd2116 in read (v=@0xb34007d8: 0, stream=...) at /opt/ros/fuerte/include/ros/serialization.h:201
#1 deserialize (t=@0xb34007d8: 0, stream=...) at /opt/ros/fuerte/include/ros/serialization.h:161
#2 next (t=@0xb34007d8: 0, this=0xb2afe9e0) at /opt/ros/fuerte/include/ros/serialization.h:716
#3 allInOne>&> (m=..., stream=...)
at /opt/ros/fuerte/include/geometry_msgs/Vector3.h:206
#4 read>> (t=..., stream=...) at /opt/ros/fuerte/include/geometry_msgs/Vector3.h:211
#5 deserialize>, ros::serialization::IStream> (t=..., stream=...)
at /opt/ros/fuerte/include/ros/serialization.h:161
#6 next>> (t=..., this=0xb2afe9e0) at /opt/ros/fuerte/include/ros/serialization.h:716
#7 allInOne>&> (m=..., stream=...)
at /opt/ros/fuerte/include/geometry_msgs/Transform.h:219
#8 read>> (t=..., stream=...)
at /opt/ros/fuerte/include/geometry_msgs/Transform.h:223
#9 deserialize>, ros::serialization::IStream> (t=..., stream=...)
at /opt/ros/fuerte/include/ros/serialization.h:161
#10 next>> (t=..., this=0xb2afe9e0) at /opt/ros/fuerte/include/ros/serialization.h:716
#11 allInOne>&> (m=..., stream=...)
at /opt/ros/fuerte/include/geometry_msgs/TransformStamped.h:257
#12 read>> (t=..., stream=...)
at /opt/ros/fuerte/include/geometry_msgs/TransformStamped.h:260
#13 deserialize>, ros::serialization::IStream> (t=..., stream=...)
at /opt/ros/fuerte/include/ros/serialization.h:161
#14 next>> (t=..., this=0xb2afe9e0) at /opt/ros/fuerte/include/ros/serialization.h:716
#15 ros::serialization::VectorSerializer>, std::allocator>>, void>::read (stream=..., v=...) at /opt/ros/fuerte/include/ros/serialization.h:358
#16 0xb6cd23fe in deserialize>, std::allocator>>, ros::serialization::IStream> (t=..., stream=...) at /opt/ros/fuerte/include/ros/serialization.h:482
#17 next>, std::allocator>>>> (
t=..., this=0xb2afe9e0) at /opt/ros/fuerte/include/ros/serialization.h:716
#18 allInOne>&> (m=..., stream=...)
at /home/name/ros/geometry/tf/msg_gen/cpp/include/tf/tfMessage.h:163
#19 read>> (t=..., stream=...)
at /home/name/ros/geometry/tf/msg_gen/cpp/include/tf/tfMessage.h:166
#20 deserialize>, ros::serialization::IStream> (t=..., stream=...) at /opt/ros/fuerte/include/ros/serialization.h:161
21 ros::SubscriptionCallbackHelperT> const> const&, void>::deserialize (this=, params=...)
at /opt/ros/fuerte/include/ros/subscription_callback_helper.h:172
#22 0xb6c47d68 in ros::MessageDeserializer::deserialize() () from /opt/ros/fuerte/lib/libroscpp.so
#23 0xb6c432f4 in ros::SubscriptionQueue::call() () from /opt/ros/fuerte/lib/libroscpp.so
#24 0xb6bf04e6 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/fuerte/lib/libroscpp.so
#25 0xb6bf00ac in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/fuerte/lib/libroscpp.so
#26 0xb6cce790 in tf::TransformListener::dedicatedListenerThread (this=0xbeffea28) at /home/name/ros/geometry/tf/include/tf/transform_listener.h:187
#27 0xb6cce4ec in operator() (p=, this=) at /usr/include/boost/bind/mem_fn_template.hpp:49
#28 operator(), boost::_bi::list0> (f=..., this=, a=...) at /usr/include/boost/bind/bind.hpp:253
#29 operator() (this=) at /usr/include/boost/bind/bind_template.hpp:20
#30 boost::detail::thread_data, boost::_bi::list1>>>::run (this=) at /usr/include/boost/thread/detail/thread.hpp:61
#31 0xb697b602 in thread_proxy () from /usr/lib/libboost_thread.so.1.46.1
#32 0xb682bed2 in start_thread () from /lib/arm-linux-gnueabihf/libpthread.so.0
#33 0xb67d2f48 in ?? () from /lib/arm-linux-gnueabihf/libc.so.6
#34 0xb67d2f48 in ?? () from /lib/arm-linux-gnueabihf/libc.so.6
Backtrace stopped: previous frame identical to this frame (corrupt stack?)
The error from the kernel:
Alignment trap: not handling instruction ed977b00 at []
Unhandled fault: alignment exception (0x011) at 0xb3d01e39
Anybody have any thoughts?
↧