Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Orb poll hrt #713

Merged
merged 10 commits into from
Jun 10, 2024
11 changes: 0 additions & 11 deletions platforms/common/uORB/Subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,17 +143,6 @@ class Subscription
return valid() ? Manager::orb_data_copy(_node, dst, _last_generation, true) : false;
}

void ack()
{
if (!valid()) {
subscribe();
}

if (valid()) {
Manager::orb_data_ack(_node, _last_generation);
}
}

/**
* Copy the struct
* @param dst The uORB message struct we are updating.
Expand Down
11 changes: 0 additions & 11 deletions platforms/common/uORB/SubscriptionInterval.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,17 +100,6 @@ class SubscriptionInterval
return false;
}

/**
* Acknowledge a new update.
*/
void ack()
{
_subscription.ack();
const hrt_abstime now = hrt_absolute_time();
// shift last update time forward, but don't let it get further behind than the interval
_last_update = math::constrain(_last_update + _interval_us, now - _interval_us, now);
}

/**
* Copy the struct if updated.
* @param dst The destination pointer where the struct will be copied.
Expand Down
5 changes: 0 additions & 5 deletions platforms/common/uORB/uORB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,6 @@ int orb_check(orb_sub_t handle, bool *updated)
return uORB::Manager::get_instance()->orb_check(handle, updated);
}

int orb_ack(orb_sub_t handle)
{
return uORB::Manager::get_instance()->orb_ack(handle);
}

int orb_exists(const struct orb_metadata *meta, int instance)
{
return uORB::Manager::orb_exists(meta, instance);
Expand Down
2 changes: 0 additions & 2 deletions platforms/common/uORB/uORB.h
Original file line number Diff line number Diff line change
Expand Up @@ -246,8 +246,6 @@ extern int orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buf
*/
extern int orb_check(orb_sub_t handle, bool *updated) __EXPORT;

extern int orb_ack(orb_sub_t handle) __EXPORT;

/**
* @see uORB::Manager::orb_exists()
*/
Expand Down
2 changes: 0 additions & 2 deletions platforms/common/uORB/uORBDeviceNode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,8 +219,6 @@ class DeviceNode
*/
bool copy(void *dst, orb_advert_t &handle, unsigned &generation);

void ack(unsigned &generation) { generation = _generation.load(); }

static bool register_callback(orb_advert_t &node_handle, SubscriptionCallback *callback_sub, int8_t poll_lock,
hrt_abstime last_update, uint32_t interval_us, uorb_cb_handle_t &cb_handle)
{
Expand Down
6 changes: 0 additions & 6 deletions platforms/common/uORB/uORBManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,12 +365,6 @@ int uORB::Manager::orb_check(orb_sub_t handle, bool *updated)
return PX4_OK;
}

int uORB::Manager::orb_ack(orb_sub_t handle)
{
((uORB::SubscriptionInterval *)handle)->ack();
return PX4_OK;
}

int uORB::Manager::orb_set_interval(orb_sub_t handle, unsigned interval)
{
((uORB::SubscriptionInterval *)handle)->set_interval_us(interval * 1000);
Expand Down
8 changes: 0 additions & 8 deletions platforms/common/uORB/uORBManager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,9 +292,6 @@ class Manager
*/
static int orb_check(orb_sub_t handle, bool *updated);


static int orb_ack(orb_sub_t handle);

/**
* Check if a topic has already been created and published (advertised)
*
Expand Down Expand Up @@ -360,11 +357,6 @@ class Manager

static uint8_t orb_get_queue_size(const orb_advert_t &node_handle) {return node(node_handle)->get_queue_size();}

static void orb_data_ack(orb_advert_t &node_handle, unsigned &generation)
{
node(node_handle)->ack(generation);
}

static bool orb_data_copy(orb_advert_t &node_handle, void *dst, unsigned &generation,
bool only_if_updated)
{
Expand Down
8 changes: 0 additions & 8 deletions src/modules/mavlink/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,3 @@ menuconfig USER_MAVLINK
depends on BOARD_PROTECTED && MODULES_MAVLINK
---help---
Put mavlink in userspace memory

menuconfig MAVLINK_UORB_POLL
bool "mavlink uorb poll in main loop"
default n
depends on MODULES_MAVLINK
---help---
Use uorb topic polling in mavlink main loop instead of
using px4_usleep for stream rate handling.
64 changes: 9 additions & 55 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,10 +134,7 @@ Mavlink::Mavlink() :

_event_sub.subscribe();
_telemetry_status_pub.advertise();

#if defined(CONFIG_MAVLINK_UORB_POLL)
_stream_poller = new MavlinkStreamPoll();
#endif
}

Mavlink::~Mavlink()
Expand Down Expand Up @@ -179,13 +176,7 @@ Mavlink::~Mavlink()
}
}

#if defined(CONFIG_MAVLINK_UORB_POLL)

if (_stream_poller) {
delete _stream_poller;
}

#endif
delete _stream_poller;

perf_free(_loop_perf);
perf_free(_loop_interval_perf);
Expand Down Expand Up @@ -2337,30 +2328,23 @@ Mavlink::task_main(int argc, char *argv[])

_task_running.store(true);

#if defined(CONFIG_MAVLINK_UORB_POLL)
int uorb_poll_error_counter = 0;
#endif
int mavlink_poll_error_counter = 0;

while (!should_exit()) {
/* main loop */
#if defined(CONFIG_MAVLINK_UORB_POLL)
int uorb_poll_ret = _stream_poller->poll(MAIN_LOOP_DELAY);

if (uorb_poll_ret < 0) {
int mavlink_poll_ret = _stream_poller->poll(MAIN_LOOP_DELAY);

if (mavlink_poll_ret < 0 && mavlink_poll_ret != -ETIMEDOUT) {
/* this is seriously bad - should be an emergency */
if (uorb_poll_error_counter < 10 || uorb_poll_error_counter % 50 == 0) {
if (mavlink_poll_error_counter < 10 || mavlink_poll_error_counter % 50 == 0) {
/* use a counter to prevent flooding (and slowing us down) */
PX4_ERR("ERROR while polling uorbs: %d", uorb_poll_ret);
PX4_ERR("ERROR while polling streams: %d", mavlink_poll_ret);
}

uorb_poll_error_counter++;
mavlink_poll_error_counter++;
}

_stream_poller->ack_all();
#else
px4_usleep(_main_loop_delay);
#endif

if (!should_transmit()) {
check_requested_subscriptions();
continue;
Expand Down Expand Up @@ -2881,43 +2865,13 @@ void Mavlink::configure_sik_radio()
}
}


int
Mavlink::register_orb_poll(uint16_t stream_id, ORB_ID *orbs, int count)
{
#if defined(CONFIG_MAVLINK_UORB_POLL)
return _stream_poller->register_orbs(stream_id, orbs, count);
#else
(void)stream_id;
(void)orbs;
(void)count;
return PX4_OK;
#endif
}

int
Mavlink::unregister_orb_poll(uint16_t stream_id)
{
#if defined(CONFIG_MAVLINK_UORB_POLL)
return _stream_poller->unregister_orbs(stream_id);
#else
(void)stream_id;
return PX4_OK;
#endif
}

int
Mavlink::set_stream_interval(MavlinkStream *stream, int interval)
{
stream->set_interval(interval);
#if defined(CONFIG_MAVLINK_UORB_POLL)
return _stream_poller->set_interval(stream->get_id(), interval / 1000);
#else
return PX4_OK;
#endif
return _stream_poller->set_interval(stream->get_id(), interval);
}


int Mavlink::start_helper(int argc, char *argv[])
{
/* create the instance in task context */
Expand Down
8 changes: 0 additions & 8 deletions src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -524,18 +524,10 @@ class Mavlink final : public ModuleParams

bool radio_status_critical() const { return _radio_status_critical; }

/**
* Register/Unregister a stream orbs for polling
*/
int register_orb_poll(uint16_t stream_id, ORB_ID *orbs, int count);
int unregister_orb_poll(uint16_t stream_id);

int set_stream_interval(MavlinkStream *stream, int interval);

private:
#if defined(CONFIG_MAVLINK_UORB_POLL)
MavlinkStreamPoll *_stream_poller {nullptr};
#endif

MavlinkReceiver _receiver;

Expand Down
Loading