move spin functions to nodehandle

This commit is contained in:
Thomas Gubler 2014-11-26 13:18:28 +01:00
parent 818a49b5a8
commit ee534b827a
5 changed files with 7 additions and 16 deletions

View File

@ -90,7 +90,7 @@ PX4_MAIN_FUNCTION(publisher)
*/
rc_channels_pub->publish(msg);
px4::spin_once();
n.spinOnce();
loop_rate.sleep();
++count;

View File

@ -85,7 +85,7 @@ PX4_MAIN_FUNCTION(subscriber)
* callbacks will be called from within this thread (the main one). px4::spin()
* will exit when Ctrl-C is pressed, or the node is shutdown by the master.
*/
px4::spin();
n.spin();
return 0;
}

View File

@ -51,10 +51,6 @@ __EXPORT uint64_t get_time_micros();
__EXPORT bool ok();
__EXPORT void spin_once();
__EXPORT void spin();
class Rate
{

View File

@ -53,6 +53,7 @@
namespace px4
{
//XXX create abstract base class
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
class NodeHandle :
private ros::NodeHandle
@ -83,6 +84,10 @@ public:
_pubs.push_back(pub);
return pub;
}
void spin() { ros::spin(); }
void spinOnce() { ros::spinOnce(); }
private:
static const uint32_t kQueueSizeDefault = 1000;
std::list<Subscriber*> _subs;

View File

@ -58,14 +58,4 @@ bool ok()
return ros::ok();
}
void spin_once()
{
ros::spinOnce();
}
void spin()
{
ros::spin();
}
}