Skip to content
Snippets Groups Projects
Commit 2f2c0440 authored by Beat Küng's avatar Beat Küng Committed by Lorenz Meier
Browse files

orb_exists: change semantics from (is published or subscribed) to (is published)

Existing users of orb_exists:
- logger (dynamic subscribe to multi-instances)
- mavlink (orb subscription)
- sdlog2
- preflightcheck (check for home_position)
- wait_for_topic shell command (it's not used)
- orb_group_count() (sensors: dynamic sensor addition)

All use-cases benefit from the changed semantics: they are really only
interested if there is a publisher, not another subscriber.
parent d83073f0
No related branches found
No related tags found
No related merge requests found
......@@ -93,4 +93,7 @@
/** Get the minimum interval at which the topic can be seen to be updated for this subscription */
#define ORBIOCGETINTERVAL _ORBIOC(16)
/** Check whether the topic is published, sets *(unsigned long *)arg to 1 if published, 0 otherwise */
#define ORBIOCISPUBLISHED _ORBIOC(17)
#endif /* _DRV_UORB_H */
......@@ -170,6 +170,10 @@ uORB::DeviceNode::open(device::file_t *filp)
return ret;
}
if (FILE_FLAGS(filp) == 0) {
return CDev::open(filp);
}
/* can only be pub or sub, not both */
return -EINVAL;
}
......@@ -405,6 +409,11 @@ uORB::DeviceNode::ioctl(device::file_t *filp, int cmd, unsigned long arg)
return OK;
case ORBIOCISPUBLISHED:
*(unsigned long *)arg = _published;
return OK;
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
......
......@@ -131,9 +131,9 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
return ERROR;
}
#if __PX4_NUTTX
#if defined(__PX4_NUTTX)
struct stat buffer;
return stat(path, &buffer);
ret = stat(path, &buffer);
#else
ret = px4_access(path, F_OK);
......@@ -141,8 +141,28 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
ret = (_remote_topics.find(meta->o_name) != _remote_topics.end()) ? OK : ERROR;
}
return ret;
#endif
if (ret == 0) {
// we know the topic exists, but it's not necessarily advertised/published yet (for example
// if there is only a subscriber)
// The open() will not lead to memory allocations.
int fd = px4_open(path, 0);
if (fd >= 0) {
unsigned long is_published;
if (px4_ioctl(fd, ORBIOCISPUBLISHED, (unsigned long)&is_published) == 0) {
if (!is_published) {
ret = ERROR;
}
}
px4_close(fd);
}
}
return ret;
}
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
......
......@@ -298,12 +298,11 @@ public:
int orb_stat(int handle, uint64_t *time) ;
/**
* Check if a topic has already been created (a publisher or a subscriber exists with
* the given instance).
* Check if a topic has already been created and published (advertised)
*
* @param meta ORB topic metadata.
* @param instance ORB instance
* @return OK if the topic exists, ERROR otherwise with errno set accordingly.
* @return OK if the topic exists, ERROR otherwise.
*/
int orb_exists(const struct orb_metadata *meta, int instance) ;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment