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">On Wed, Jun 30, 2010 at 5:46 PM, Daniel Stonier <span dir="ltr"><<a href="mailto:d.stonier@gmail.com">d.stonier@gmail.com</a>></span> wrote:<br>

<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">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>
_______________________________________________<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>
</blockquote></div><br></div>