On 8 July 2010 23:51, Rob Wheeler wrote: > Just out of curiosity...Is your arm processor running in big-endian or > little-endian mode? > > -R > > > Little endian. > On Thu, Jul 8, 2010 at 3:43 AM, Daniel Stonier wrote: > >> Ok, got waylaid with other jobs for a while, but having a look at it >> again. >> >> Got into it with a debugger, and found it hanging at >> roslib/include/ros/serialization.h at >> >> ROS_CREATE_SIMPLE_SERIALIZER(double); >> >> I've got a backtrace obtained by attaching to the program as soon as it >> hung - pasted below. I also decided to test doubles in a more serious way on >> the board. >> >> - Remade the srv's with int32 rather than float64 and it ran fine. >> - Recompiled the entire ros tree and the original float64 program making >> sure I had the correct use flags for the board (-mfpu=vfp), still failed. >> - Wrote a similar program passing std_msgs::Float64 back and forth between >> topics, that worked! >> >> ****************************************** >> Backtrace ****************************************** >> >> 0x0001e378 in >> ros::serialization::Serializer::write ( >> stream=..., v=304.18260199999997) >> at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:198 >> >> warning: Source file is more recent than executable. >> 198 ROS_CREATE_SIMPLE_SERIALIZER(double); >> (gdb) bt >> #0 0x0001e378 in >> ros::serialization::Serializer::write ( >> stream=..., v=304.18260199999997) >> at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:198 >> #1 0x0001dcec in ros::serialization::serialize> ros::serialization::OStream> (stream=..., >> t=@0x48af0) at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:149 >> #2 0x0001ed4c in next (stream=..., m=...) >> at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:741 >> #3 >> ros::serialization::Serializer >> > >::allInOne> rpc_latency::float_ping_pongResponse_ > const&> >> (stream=..., m=...) >> at >> /opt/iclebo/ycs/ycs_tools/rpc_latency/srv_gen/cpp/include/rpc_latency/float_ping_pong.h:304 >> #4 0x0001eab0 in >> ros::serialization::Serializer >> > >::write> rpc_latency::float_ping_pongResponse_ > > (stream=..., >> t=...) >> at >> /opt/iclebo/ycs/ycs_tools/rpc_latency/srv_gen/cpp/include/rpc_latency/float_ping_pong.h:307 >> #5 0x0001e2b4 in >> ros::serialization::serialize >> >, ros::serialization::OStream> (stream=..., t=...) >> at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:149 >> #6 0x0001dae4 in >> ros::serialization::serializeServiceResponse >> > > (ok=true, message=...) >> at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:831 >> #7 0x0001cd70 in >> ros::ServiceCallbackHelperT >> >, rpc_latency::float_ping_pongResponse_ > > >::call ( >> this=0x45f20, params=...) >> at /opt/iclebo/ros/core/roscpp/include/ros/service_callback_helper.h:189 >> #8 0x402336d0 in ros::ServiceCallback::call (this=0x49a10) >> at /opt/iclebo/ros/core/roscpp/src/libros/service_publication.cpp:123 >> #9 0x40252c28 in ros::CallbackQueue::callOneCB (this=0x3b918, tls=0x48f90) >> at /opt/iclebo/ros/core/roscpp/src/libros/callback_queue.cpp:360 >> #10 0x4025258c in ros::CallbackQueue::callAvailable (this=0x3b918, >> timeout=...) >> at /opt/iclebo/ros/core/roscpp/src/libros/callback_queue.cpp:320 >> >> >> On 1 July 2010 14:17, Josh Faust wrote: >> >>> Are you able to break into it in a debugger to see where it's using cpu? >>> Do topics work properly? >>> >>> Josh >>> >>> On Wed, Jun 30, 2010 at 5:46 PM, Daniel Stonier wrote: >>> >>>> Hi all, >>>> >>>> We're trying to get ros running on an armv6 core here and hitting a >>>> few issues. If anyone has any insight on how to go about tracking down >>>> the issues that would be great. >>>> >>>> Some general details about the problem: >>>> >>>> It's an armv6 core running a custom gentoo with cturtle. The example >>>> programs I have to test with are a simple client-server pair. The >>>> client pings the server with a timestamped rpc service request, the >>>> server too, timestamps and then sends a response. When the response is >>>> received by the client, it outputs and terminates. >>>> >>>> So it's pretty simple, no more than a few lines of code in server and >>>> client (I've added the code below). End result though, the server >>>> catches the request, at which point both client and server hang and >>>> server cpu % goes through the roof. Since the code is simple, I'm >>>> figuring it must be behind the scenes somewhere (maybe in the rosdep >>>> library builds or system configuration?) I'm not sure how to track >>>> down the issue though - anyone have any ideas? >>>> >>>> Cheers, >>>> Daniel. >>>> >>>> ***************************** client.cpp ***************************** >>>> >>>> class LatencyClient { >>>> public: >>>> LatencyClient() : >>>> client(node.serviceClient< rpc_latency::ping_pong >>>> >("rpc_latency")) >>>> {} >>>> /** >>>> * Latency benchmarking service request handler. This initiates >>>> the request and waits >>>> * for the response. Handling is done in main(). >>>> * @return bool - success or failure of the request. >>>> */ >>>> bool ping_pong() { >>>> rpc_latency::ping_pong srv; >>>> TimeStamp send_stamp; >>>> TimeStamp final_stamp; >>>> >>>> srv.request.ping_time = static_cast(send_stamp.stamp()); >>>> if ( client.call(srv) ) { >>>> final_stamp.stamp(); >>>> ROS_INFO("Send Time : %lf", srv.response.pong_time - >>>> srv.request.ping_time); >>>> ROS_INFO("Return Time : %lf", >>>> static_cast(final_stamp) - srv.response.pong_time); >>>> ROS_INFO("Round Trip : %lf", >>>> static_cast(final_stamp - send_stamp) ); >>>> return true; >>>> } else { >>>> ROS_ERROR("Failed to call service rpc_latency"); >>>> return false; >>>> } >>>> } >>>> >>>> private: >>>> ros::NodeHandle node; >>>> ros::ServiceClient client; >>>> }; >>>> >>>> int main(int argc, char **argv) { >>>> ros::init(argc, argv, "rpc_latency_client"); >>>> >>>> LatencyClient latency; >>>> latency.ping_pong(); >>>> return 0; >>>> } >>>> >>>> ***************************** server.cpp ***************************** >>>> >>>> class LatencyServer { >>>> public: >>>> LatencyServer() : >>>> service (node.advertiseService("rpc_latency", >>>> &LatencyServer::ping_pong, this)) >>>> {} >>>> >>>> void spin() { >>>> ros::spin(); >>>> } >>>> bool ping_pong(rpc_latency::ping_pong::Request &request, >>>> rpc_latency::ping_pong::Response &response ) { >>>> response.pong_time = timestamp.stamp(); >>>> ROS_INFO("TimeStamp: %lf", static_cast(timestamp) ); >>>> return true; >>>> } >>>> >>>> private: >>>> TimeStamp timestamp; >>>> ros::NodeHandle node; >>>> ros::ServiceServer service; >>>> }; >>>> >>>> int main(int argc, char **argv) { >>>> ros::init(argc, argv, "rpc_latency_server"); >>>> >>>> LatencyServer latency_server; >>>> latency_server.spin(); >>>> return 0; >>>> } >>>> >>>> >>>> >>>> -- >>>> Phone : +82-10-5400-3296 (010-5400-3296) >>>> Home: http://snorriheim.dnsdojo.com/ >>>> Yujin Robot: http://www.yujinrobot.com/ >>>> Embedded Control Libraries: >>>> http://snorriheim.dnsdojo.com/redmine/wiki/ecl >>>> _______________________________________________ >>>> ros-users mailing list >>>> ros-users@code.ros.org >>>> https://code.ros.org/mailman/listinfo/ros-users >>>> >>> >>> >>> _______________________________________________ >>> ros-users mailing list >>> ros-users@code.ros.org >>> https://code.ros.org/mailman/listinfo/ros-users >>> >>> >> >> >> -- >> Phone : +82-10-5400-3296 (010-5400-3296) >> Home: http://snorriheim.dnsdojo.com/ >> Yujin Robot: http://www.yujinrobot.com/ >> Embedded Control Libraries: >> http://snorriheim.dnsdojo.com/redmine/wiki/ecl >> >> _______________________________________________ >> ros-users mailing list >> ros-users@code.ros.org >> https://code.ros.org/mailman/listinfo/ros-users >> >> > > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > > -- Phone : +82-10-5400-3296 (010-5400-3296) Home: http://snorriheim.dnsdojo.com/ Yujin Robot: http://www.yujinrobot.com/ Embedded Control Libraries: http://snorriheim.dnsdojo.com/redmine/wiki/ecl