mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
make px4::ok work, use it in px4::spin
This commit is contained in:
parent
cefccc0037
commit
a9c1e4ad61
@ -102,9 +102,6 @@ include_directories(
|
||||
## Declare a cpp library
|
||||
add_library(px4
|
||||
src/platforms/ros/px4_ros_impl.cpp
|
||||
src/platforms/ros/px4_publisher.cpp
|
||||
src/platforms/ros/px4_subscriber.cpp
|
||||
src/platforms/ros/px4_nodehandle.cpp
|
||||
)
|
||||
|
||||
target_link_libraries(px4
|
||||
|
||||
@ -35,9 +35,6 @@
|
||||
# NuttX / uORB adapter library
|
||||
#
|
||||
|
||||
SRCS = px4_nuttx_impl.cpp \
|
||||
px4_publisher.cpp \
|
||||
px4_subscriber.cpp \
|
||||
px4_nodehandle.cpp
|
||||
SRCS = px4_nuttx_impl.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
@ -37,27 +37,8 @@
|
||||
* PX4 Middleware Wrapper Nodehandle
|
||||
*/
|
||||
#include <px4.h>
|
||||
#include <platforms/px4_nodehandle.h>
|
||||
|
||||
namespace px4
|
||||
{
|
||||
bool task_should_exit = false;
|
||||
|
||||
|
||||
void NodeHandle::spinOnce() {
|
||||
/* Loop through subscriptions, call callback for updated subscriptions */
|
||||
uORB::SubscriptionNode *sub = _subs.getHead();
|
||||
int count = 0;
|
||||
|
||||
while (sub != nullptr) {
|
||||
if (count++ > kMaxSubscriptions) {
|
||||
PX4_WARN("exceeded max subscriptions");
|
||||
break;
|
||||
}
|
||||
|
||||
sub->update();
|
||||
sub = sub->getSibling();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -54,9 +54,4 @@ uint64_t get_time_micros()
|
||||
return hrt_absolute_time();
|
||||
}
|
||||
|
||||
bool ok()
|
||||
{
|
||||
return !task_should_exit;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -49,7 +49,12 @@ __EXPORT void init(int argc, char *argv[], const char *process_name);
|
||||
|
||||
__EXPORT uint64_t get_time_micros();
|
||||
|
||||
__EXPORT bool ok();
|
||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||
bool ok() { return ros::ok(); }
|
||||
#else
|
||||
extern bool task_should_exit;
|
||||
bool ok() { return !task_should_exit; }
|
||||
#endif
|
||||
|
||||
class Rate
|
||||
{
|
||||
@ -64,6 +69,4 @@ private:
|
||||
|
||||
};
|
||||
|
||||
extern bool task_should_exit;
|
||||
|
||||
} // namespace px4
|
||||
|
||||
@ -41,6 +41,7 @@
|
||||
/* includes for all platforms */
|
||||
#include "px4_subscriber.h"
|
||||
#include "px4_publisher.h"
|
||||
#include "px4_middleware.h"
|
||||
|
||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||
/* includes when building for ros */
|
||||
@ -126,10 +127,24 @@ public:
|
||||
return pub;
|
||||
}
|
||||
|
||||
void spinOnce();
|
||||
void spinOnce() {
|
||||
/* Loop through subscriptions, call callback for updated subscriptions */
|
||||
uORB::SubscriptionNode *sub = _subs.getHead();
|
||||
int count = 0;
|
||||
|
||||
while (sub != nullptr) {
|
||||
if (count++ > kMaxSubscriptions) {
|
||||
PX4_WARN("exceeded max subscriptions");
|
||||
break;
|
||||
}
|
||||
|
||||
sub->update();
|
||||
sub = sub->getSibling();
|
||||
}
|
||||
}
|
||||
|
||||
void spin() {
|
||||
while (true) { //XXX check for termination
|
||||
while (ok()) {
|
||||
const int timeout_ms = 100;
|
||||
/* Only continue in the loop if the nodehandle has subscriptions */
|
||||
if (_sub_min_interval == nullptr) {
|
||||
|
||||
@ -53,9 +53,4 @@ uint64_t get_time_micros()
|
||||
return time.sec * 1e6 + time.nsec / 1000;
|
||||
}
|
||||
|
||||
bool ok()
|
||||
{
|
||||
return ros::ok();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user