Hi Felix,<br><br>I'm still having trouble finding following lines in the tutorial:<br style="font-family: courier new,monospace;"><b><span style="font-family: courier new,monospace;">>>  while (ros::ok())</span><br style="font-family: courier new,monospace;">

<span style="font-family: courier new,monospace;">
>>    ros::spinOnce();</span><br style="font-family: courier new,monospace;"></b><br>Can you give the full link to the page this is in?  This should probably be changed to a <b><span style="font-family: courier new,monospace;">ros::spin()</span></b><br>

<br><b>Waiting for Server:</b><br>Instead of calling <b><span style="font-family: courier new,monospace;">waitForServer()</span></b>, you can repeatedly call <b><span style="font-family: courier new,monospace;">isServerConnected()</span></b><br>

Refer to the docs: <a href="http://www.ros.org/doc/api/actionlib/html/classactionlib_1_1SimpleActionClient.html#af3a32dd1b6e1486977c1dc99c98e627d">SimpleActionClient::isServerConnected()</a><br>The resulting code will look something like:<br>

<br><b><span style="font-family: courier new,monospace;">  while (ros::ok() && !client.isServerConnected())<br>  { <br></span><span style="font-family: courier new,monospace;">    ros::Duration(0.1).sleep();</span><br>

<span style="font-family: courier new,monospace;">   
ros::spinOnce();<br></span><span style="font-family: courier new,monospace;">  }</span><br></b><br>It sounds like you've resolved your other ActionClient issues, but definitely let me know if you have any more questions.<br>

<br>Vijay<br><br><div class="gmail_quote">On Thu, Feb 3, 2011 at 7:57 AM, Felix Ingrand <span dir="ltr"><<a href="mailto:felix@laas.fr">felix@laas.fr</a>></span> wrote:<br><blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">

OK... found it...<br>
<br>
I should blame myself... for a beginner mistake (I guess some people are always beginner)<br>
<br>
The client I created was local to my function, hence was on the stack and would not survive the function call. So the whole thing was only working when the spin etc... were local to this scope... for some stupid reasons I though that C++ objects were created on the heap, not the stack... Using new and pointers immediately solved the problem.<br>


<br>
Sorry again for this, and thanks for you explanation. In fact, I plan to use the not_threaded version and properly handle the waitForServer (with proper timeout).<br>
<br>
The good news is that I can now call ROS actions from OpenPRS, and get proper feedback. yesss....<br>
<br>
Thanks again,<br>
<div><div></div><div class="h5"><br>
<br>
On 3 févr. 2011, at 15:34, Felix Ingrand wrote:<br>
<br>
> In fact, I try removing (in my test code ) the ros::spin after the sendGoal, and I only get 2 callbacks (the active and the first feedback) then the client remains silent (but still alive). So I am not quite sure they run a ros::spin() in this thread.<br>


><br>
> In any case, I am back to the original problem... which boils down now to:<br>
><br>
> a ros::spin () or periodic call to ros::spinOnce() are required to get the client to properly run. if I put them in the function which call the sendGoal, it works (like with the fibonacci_callback_client exemple), if I make the  periodic calls to ros::spinOnce() later in another function, it does not work (in fact ros:ok() returns false then).<br>


><br>
> I hope somebody has an idea as to why this is so.<br>
><br>
> Thanks for your help,<br>
><br>
> On 3 févr. 2011, at 15:00, Lorenz M=F6senlechner wrote:<br>
><br>
>> Hi,<br>
>><br>
>>><br>
>>> On 3 févr. 2011, at 14:49, Lorenz M=F6senlechner wrote:<br>
>>><br>
>>>> Hi,<br>
>>>><br>
>>>> Where did you actually find that code? I cannot find it somehow.<br>
>>><br>
>>><br>
>>> <a href="http://www.ros.org/wiki/actionlib/Tutorials" target="_blank">http://www.ros.org/wiki/actionlib/Tutorials</a><br>
>><br>
>> I was trying to find it there but couldn't find it in the first place<br>
>> :) Now I found it and I also don't quite understand why they use an<br>
>> explicit spinner instead of a sendGoalAndWait. Maybe one of the Willow<br>
>> guys can clarify here.<br>
>><br>
>> Lorenz<br>
>><br>
>>><br>
>>><br>
>>>><br>
>>>> In the code below, a spin loop is required because the main function<br>
>>>> would terminate early otherwise. If you use ac.sendGoalAndWait, the<br>
>>>> explicit spin shouldn't be reqired.<br>
>>>><br>
>>>> Btw. I guess your node eats up a lot of CPU because of the busy spin<br>
>>>> loop. As far as I remember, spinOnce returns immediately if there are<br>
>>>> no messages to handle. I guess it would be better to either use<br>
>>>> ros::spin() or add a ros rate with a sleep or so.<br>
>>><br>
>>> Sure, but this was just for testing, in y "regular" code, I call<br>
>>> spinOnce at 100 Hz.<br>
>>><br>
>>><br>
>>>><br>
>>>> Lorenz<br>
>>>><br>
>>>><br>
>>>>> Still, another thing which puzzle me, if the action client does the ros::spin(); why is there one following the sendGoal in the tutorial code?<br>
>>>>><br>
>>>>> int main (int argc, char **argv)<br>
>>>>> {<br>
>>>>> ros::init(argc, argv, "test_fibonacci_callback");<br>
>>>>><br>
>>>>> // Create the action client<br>
>>>>> Client ac("fibonacci", true);<br>
>>>>><br>
>>>>> ROS_INFO("Waiting for action server to start.");<br>
>>>>> ac.waitForServer();<br>
>>>>> ROS_INFO("Action server started, sending goal.");<br>
>>>>><br>
>>>>> // Send Goal<br>
>>>>> FibonacciGoal goal;<br>
>>>>> goal.order = 20;<br>
>>>>> ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);<br>
>>>>><br>
>>>>> while (ros::ok())<br>
>>>>>  ros::spinOnce();<br>
>>>>><br>
>>>>> return 0;<br>
>>>>> }<br>
>>>>><br>
>>>>> Moreover, why do not I see the other callbacks being called? and why do I see them being called if I add a spin just after the sendGoal... this is still not quite consistent.<br>
>>>>><br>
>>>>> On 3 fÃ∞©vr. 2011, at 14:05, Felix Ingrand wrote:<br>
>>>>><br>
>>>>>> Thanks,  now that makes sense.<br>
>>>>>><br>
>>>>>> Still, this does not explain why later my ros::ok() returns false... or does that mean that only the thread which does the spin is allowed to do a ros::ok() and ros::spin()?<br>
>>>>>><br>
>>>>>> In any case, I will try your method.<br>
>>>>>><br>
>>>>>> As a side question, is it possible to make a waitForServer non blocking? (e.g. returning false until the server has started)<br>
>>>>>><br>
>>>>>> Thanks again, that clarifies my understanding.<br>
>>>>>><br>
>>>>>><br>
>>>>>> On 3 fÃ∞©vr. 2011, at 13:42, Lorenz MÃ∞¶senlechner wrote:<br>
>>>>>><br>
>>>>>>> Hi,<br>
>>>>>>><br>
>>>>>>> in your example you set the spin_thread parameter of the action client<br>
>>>>>>> to true which causes it to internally start a thread that calls<br>
>>>>>>> ros::spin(). If you don't want that, you need to set the spin_thread<br>
>>>>>>> parameter to false. You also need to remove your waitForServer call<br>
>>>>>>> then since it would block forever.<br>
>>>>>>><br>
>>>>>>> Lorenz<br>
>>>>>>><br>
>>>>>>>><br>
>>>>>>>> On 3 fÃ∞â√ıÃ≠©vr. 2011, at 11:36, Lorenz MÃ∞â√ıÃ≠¶senlechner wrote:<br>
>>>>>>>><br>
>>>>>>>>> Hi,<br>
>>>>>>>>><br>
>>>>>>>>> the action client starts up its own spin thread per default. You can<br>
>>>>>>>>> disable it by instantiating it as follows:<br>
>>>>>>>>><br>
>>>>>>>>> Client ac("fibonacci", false);<br>
>>>>>>>>><br>
>>>>>>>>> But you need to be a little bit careful with that. If you don't have a<br>
>>>>>>>>> separate spin thread running, waitForServer will not work. It will<br>
>>>>>>>>> just block because it needs a spinner running in order to get message<br>
>>>>>>>>> callbacks for the action's status topic.<br>
>>>>>>>><br>
>>>>>>>> I cannot do this, as my program is not multithreaded (at least for now).<br>
>>>>>>>><br>
>>>>>>>>><br>
>>>>>>>>> If I understand your example correctly, you are trying to start up an<br>
>>>>>>>>> action client, send a goal and sort of block until you receive a<br>
>>>>>>>>> result. After you got it, you try to shut down the whole ros loop<br>
>>>>>>>>> again.<br>
>>>>>>>><br>
>>>>>>>> I did that just for testing callbacks are properly working. But what I want to do is start an action client, and then have my spinOnce (which is executed in the same main thread but later and in other part of the code) properly calling the callback. But for some reasons if the ros::ok()/ros::spinOnce() code is just after the sendGoal, it works, but if it is in other part of the code, it fails...<br>


>>>>>>>><br>
>>>>>>>>> Can't you just let the spinner run and use ac.sendGoalAndWait<br>
>>>>>>>>> instead to do a blocking call?<br>
>>>>>>>>><br>
>>>>>>>>> Lorenz<br>
>>>>>>>>><br>
>>>>>>>>>> Hi,<br>
>>>>>>>>>><br>
>>>>>>>>>> I am getting OpenPRS connected to ROS to supervise our PR2.<br>
>>>>>>>>>><br>
>>>>>>>>>> So far, I have done some testing with topics (subscribing and publishing)/services and all is good.<br>
>>>>>>>>>><br>
>>>>>>>>>> Trying to play with SimpleAction (which seem to be the best tool in ROS to supervise nodes) I am witnessing a weird problem.<br>
>>>>>>>>>><br>
>>>>>>>>>> - the version of OpenPRS I use is NOT multithreaded, but it uses SIGALARM<br>
>>>>>>>>>> - I have an evaluable predicate which automatically and periodically (100 Hz) call<br>
>>>>>>>>>> if (ros::ok()) {<br>
>>>>>>>>>> ros::spinOnce();<br>
>>>>>>>>>> }<br>
>>>>>>>>>> and this takes care of all the callbacks (and indeed, it works with subscribed topics).<br>
>>>>>>>>>><br>
>>>>>>>>>> Now, when I create a SimpleAction client (using the Fibonacci server example) with this code:<br>
>>>>>>>>>><br>
>>>>>>>>>> if (PUGetOprsParameters(terms, 1,<br>
>>>>>>>>>>                        INTEGER, &seq)) {<br>
>>>>>>>>>> // Create the action client<br>
>>>>>>>>>> Client ac("fibonacci", true);<br>
>>>>>>>>>><br>
>>>>>>>>>> ROS_INFO("Waiting for action server to start.");<br>
>>>>>>>>>> ac.waitForServer();<br>
>>>>>>>>>> ROS_INFO("Action server started, sending goal.");<br>
>>>>>>>>>><br>
>>>>>>>>>> // Send Goal<br>
>>>>>>>>>> learning_actionlib::FibonacciGoal goal;<br>
>>>>>>>>>> goal.order = seq;<br>
>>>>>>>>>> ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);<br>
>>>>>>>>>><br>
>>>>>>>>>> It works, and shortly after (even before calling spinOnce explicitly), I get the activeCb called (once) and the feedbackCB called (only once with seq value 3). So I guess that there is an implicit spinOnce done somewhere here in the sendGoal.<br>


>>>>>>>>>><br>
>>>>>>>>>> If I put the following code just after the sendGoal:<br>
>>>>>>>>>><br>
>>>>>>>>>> while (ros::ok()) {<br>
>>>>>>>>>> ros::spinOnce();             // This will call the callbacks.<br>
>>>>>>>>>> }<br>
>>>>>>>>>><br>
>>>>>>>>>> Then the sequence callback is called for all the values and the doneCB (to which I added at the end a ros::Shutdown to let the ros::ok return false and leave the loop) is also called. good...<br>


>>>>>>>>>><br>
>>>>>>>>>> But if I comment this loop, and rely on the evaluable predicate which will be called later by the OpenPRS main loop, then ros::ok() return true until I call the function doing the sendGoal, after which it returns false.<br>


>>>>>>>>>><br>
>>>>>>>>>> I am running all this on Ubuntu 10.4 (based on the VirtualBox machine proposed by WG, and properly up to date).<br>
>>>>>>>>>><br>
>>>>>>>>>> Before I dig further, any idea what I may be doing wrong here? I can see that SimpleActionClient starts a lot of threads, still the code I use to spin ROS after the sendGoal OR in the evaluable predicate are executing in the same thread (the main one)... why does it work when it is just "after" the sendGoal and not a few milliseconds later?<br>


>>>>>>>>>><br>
>>>>>>>>>> Moreover, the SIGALARM handler does NOT execute the spinOnce, it merely flip a flag to tell the OpenPRS main loop to check for evaluable predicates.<br>
>>>>>>>>>><br>
>>>>>>>>>> Thanks for any help,<br>
>>>>>>>>>><br>
>>>>>>>>>> PS: is there a way to trace/see what is the reason why a node is suddenly returning ros::ok() false?<br>
>>>>>>>>><br>
>>>>>>>><br>
>>>>>>><br>
>>>>>><br>
>>>>><br>
>>>><br>
>>><br>
>><br>
>> --<br>
>> Lorenz Mösenlechner            | <a href="mailto:moesenle@in.tum.de">moesenle@in.tum.de</a><br>
>> Technische Universität München | Boltzmannstr. 3<br>
>> 85748 Garching bei München     | Germany<br>
>> <a href="http://ias.cs.tum.edu/" target="_blank">http://ias.cs.tum.edu/</a>         | Tel: +49 (89) 289-26910<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>
> --<br>
>     Felix<br>
> Graphical design beauty <a href="http://tinyurl.com/28cjdlh" target="_blank">http://tinyurl.com/28cjdlh</a><br>
><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>
<br>
</div></div><font color="#888888">--<br>
     Felix<br>
Il ne vous reste plus qu'une heure, quarante six minutes et quarante trois secondes de tranquillité d'esprit:<br>
<a href="http://tinyurl.com/5mlnfc" target="_blank">http://tinyurl.com/5mlnfc</a><br>
</font><div><div></div><div class="h5"><br>
<br>
<br>
<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>
</div></div></blockquote></div><br><br clear="all"><br>-- <br>Vijay Pradeep<br>
Systems Engineer<br>
Willow Garage, Inc.<br>
<a href="mailto:tfoote@willowgarage.com" target="_blank"><span></span></a><a href="mailto:vpradeep@willowgarage.com" target="_blank">vpradeep@willowgarage.com</a><br>
<br>