<div>Ok, got waylaid with other jobs for a while, but having a look at it again.<br></div><div><br></div><div>Got into it with a debugger, and found it hanging at roslib/include/ros/serialization.h at</div><div><br></div><div>
ROS_CREATE_SIMPLE_SERIALIZER(double);</div><div><br></div><div>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.</div>
<div><br></div><div>- Remade the srv's with int32 rather than float64 and it ran fine.</div><div>- 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.</div>
<div>- Wrote a similar program passing std_msgs::Float64 back and forth between topics, that worked!</div><div><br></div><div>****************************************** Backtrace ******************************************</div>
<div><br></div><div>0x0001e378 in ros::serialization::Serializer<double>::write<ros::serialization::OStream> (<br>    stream=..., v=304.18260199999997)<br>    at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:198<br>
<br>warning: Source file is more recent than executable.<br>198     ROS_CREATE_SIMPLE_SERIALIZER(double);<br>(gdb) bt<br>#0  0x0001e378 in ros::serialization::Serializer<double>::write<ros::serialization::OStream> (<br>
    stream=..., v=304.18260199999997)<br>    at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:198<br>#1  0x0001dcec in ros::serialization::serialize<double, ros::serialization::OStream> (stream=..., <br>    t=@0x48af0) at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:149<br>
#2  0x0001ed4c in next<double> (stream=..., m=...)<br>    at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:741<br>#3  ros::serialization::Serializer<rpc_latency::float_ping_pongResponse_<std::allocator<void> > >::allInOne<ros::serialization::OStream, rpc_latency::float_ping_pongResponse_<std::allocator<void> > const&> (stream=..., m=...)<br>
    at /opt/iclebo/ycs/ycs_tools/rpc_latency/srv_gen/cpp/include/rpc_latency/float_ping_pong.h:304<br>#4  0x0001eab0 in ros::serialization::Serializer<rpc_latency::float_ping_pongResponse_<std::allocator<void> > >::write<ros::serialization::OStream, rpc_latency::float_ping_pongResponse_<std::allocator<void> > > (stream=..., t=...)<br>
    at /opt/iclebo/ycs/ycs_tools/rpc_latency/srv_gen/cpp/include/rpc_latency/float_ping_pong.h:307<br>#5  0x0001e2b4 in ros::serialization::serialize<rpc_latency::float_ping_pongResponse_<std::allocator<void> >, ros::serialization::OStream> (stream=..., t=...)<br>
    at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:149<br>#6  0x0001dae4 in ros::serialization::serializeServiceResponse<rpc_latency::float_ping_pongResponse_<std::allocator<void> > > (ok=true, message=...)<br>
    at /opt/iclebo/ros/core/roslib/include/ros/serialization.h:831<br>#7  0x0001cd70 in ros::ServiceCallbackHelperT<ros::ServiceSpec<rpc_latency::float_ping_pongRequest_<std::allocator<void> >, rpc_latency::float_ping_pongResponse_<std::allocator<void> > > >::call (<br>
    this=0x45f20, params=...)<br>    at /opt/iclebo/ros/core/roscpp/include/ros/service_callback_helper.h:189<br>#8  0x402336d0 in ros::ServiceCallback::call (this=0x49a10)<br>    at /opt/iclebo/ros/core/roscpp/src/libros/service_publication.cpp:123<br>
#9  0x40252c28 in ros::CallbackQueue::callOneCB (this=0x3b918, tls=0x48f90)<br>    at /opt/iclebo/ros/core/roscpp/src/libros/callback_queue.cpp:360<br>#10 0x4025258c in ros::CallbackQueue::callAvailable (this=0x3b918, timeout=...)<br>
    at /opt/iclebo/ros/core/roscpp/src/libros/callback_queue.cpp:320<br><br></div><br><div class="gmail_quote">On 1 July 2010 14:17, Josh Faust <span dir="ltr"><<a href="mailto:jfaust@willowgarage.com">jfaust@willowgarage.com</a>></span> wrote:<br>
<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">Are you able to break into it in a debugger to see where it's using cpu?  Do topics work properly?<div><br></div><div>
Josh<br><br><div class="gmail_quote"><div><div class="h5">On Wed, Jun 30, 2010 at 5:46 PM, Daniel Stonier <span dir="ltr"><<a href="mailto:d.stonier@gmail.com" target="_blank">d.stonier@gmail.com</a>></span> wrote:<br>


</div></div><blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex"><div><div class="h5">Hi all,<br>
<br>
We're trying to get ros running on an armv6 core here and hitting a<br>
few issues. If anyone has any insight on how to go about tracking down<br>
the issues that would be great.<br>
<br>
Some general details about the problem:<br>
<br>
It's an armv6 core running a custom gentoo with cturtle. The example<br>
programs I have to test with are a simple client-server pair. The<br>
client pings the server with a timestamped rpc service request, the<br>
server too, timestamps and then sends a response. When the response is<br>
received by the client, it outputs and terminates.<br>
<br>
So it's pretty simple, no more than a few lines of code in server and<br>
client (I've added the code below). End result though, the server<br>
catches the request, at which point both client and server hang and<br>
server cpu % goes through the roof. Since the code is simple, I'm<br>
figuring it must be behind the scenes somewhere (maybe in the rosdep<br>
library builds or system configuration?)  I'm not sure how to track<br>
down the issue though - anyone have any ideas?<br>
<br>
Cheers,<br>
Daniel.<br>
<br>
***************************** client.cpp *****************************<br>
<br>
class LatencyClient {<br>
public:<br>
    LatencyClient() :<br>
        client(node.serviceClient< rpc_latency::ping_pong >("rpc_latency"))<br>
    {}<br>
    /**<br>
     * Latency benchmarking service request handler. This initiates<br>
the request and waits<br>
     * for the response. Handling is done in main().<br>
     * @return bool - success or failure of the request.<br>
     */<br>
    bool ping_pong() {<br>
        rpc_latency::ping_pong srv;<br>
        TimeStamp send_stamp;<br>
        TimeStamp final_stamp;<br>
<br>
        srv.request.ping_time = static_cast<double>(send_stamp.stamp());<br>
        if ( client.call(srv) ) {<br>
            final_stamp.stamp();<br>
            ROS_INFO("Send   Time : %lf", srv.response.pong_time -<br>
srv.request.ping_time);<br>
            ROS_INFO("Return Time : %lf",<br>
static_cast<double>(final_stamp) - srv.response.pong_time);<br>
            ROS_INFO("Round  Trip : %lf",<br>
static_cast<double>(final_stamp - send_stamp) );<br>
            return true;<br>
        } else {<br>
            ROS_ERROR("Failed to call service rpc_latency");<br>
            return false;<br>
        }<br>
    }<br>
<br>
private:<br>
    ros::NodeHandle node;<br>
    ros::ServiceClient client;<br>
};<br>
<br>
int main(int argc, char **argv) {<br>
    ros::init(argc, argv, "rpc_latency_client");<br>
<br>
    LatencyClient latency;<br>
    latency.ping_pong();<br>
    return 0;<br>
}<br>
<br>
***************************** server.cpp *****************************<br>
<br>
class LatencyServer {<br>
public:<br>
    LatencyServer() :<br>
        service (node.advertiseService("rpc_latency",<br>
&LatencyServer::ping_pong, this))<br>
    {}<br>
<br>
    void spin() {<br>
        ros::spin();<br>
    }<br>
    bool ping_pong(rpc_latency::ping_pong::Request  &request,<br>
                   rpc_latency::ping_pong::Response &response ) {<br>
        response.pong_time = timestamp.stamp();<br>
        ROS_INFO("TimeStamp: %lf", static_cast<double>(timestamp) );<br>
        return true;<br>
    }<br>
<br>
private:<br>
    TimeStamp timestamp;<br>
    ros::NodeHandle node;<br>
    ros::ServiceServer service;<br>
};<br>
<br>
int main(int argc, char **argv) {<br>
    ros::init(argc, argv, "rpc_latency_server");<br>
<br>
    LatencyServer latency_server;<br>
    latency_server.spin();<br>
    return 0;<br>
}<br>
<br>
<br>
<br>
--<br>
Phone : +82-10-5400-3296 (010-5400-3296)<br>
Home: <a href="http://snorriheim.dnsdojo.com/" target="_blank">http://snorriheim.dnsdojo.com/</a><br>
Yujin Robot: <a href="http://www.yujinrobot.com/" target="_blank">http://www.yujinrobot.com/</a><br>
Embedded Control Libraries: <a href="http://snorriheim.dnsdojo.com/redmine/wiki/ecl" target="_blank">http://snorriheim.dnsdojo.com/redmine/wiki/ecl</a><br></div></div>
_______________________________________________<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></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><br clear="all"><br>-- <br>Phone : +82-10-5400-3296 (010-5400-3296)<br>Home: <a href="http://snorriheim.dnsdojo.com/">http://snorriheim.dnsdojo.com/</a><br>Yujin Robot: <a href="http://www.yujinrobot.com/">http://www.yujinrobot.com/</a><br>
Embedded Control Libraries: <a href="http://snorriheim.dnsdojo.com/redmine/wiki/ecl">http://snorriheim.dnsdojo.com/redmine/wiki/ecl</a><br>