Browse Source

uORB add ORB_COMMUNICATOR define to enable remote uORB

sbg
Daniel Agar 7 years ago committed by Lorenz Meier
parent
commit
8599495082
  1. 2
      cmake/configs/posix_eagle_hil.cmake
  2. 1
      cmake/configs/posix_eagle_muorb.cmake
  3. 1
      cmake/configs/posix_sdflight_default.cmake
  4. 2
      cmake/configs/posix_sdflight_legacy.cmake
  5. 1
      cmake/configs/posix_sitl_default.cmake
  6. 1
      cmake/configs/qurt_eagle_hil.cmake
  7. 1
      cmake/configs/qurt_eagle_muorb.cmake
  8. 1
      cmake/configs/qurt_eagle_travis.cmake
  9. 1
      cmake/configs/qurt_sdflight_default.cmake
  10. 1
      cmake/configs/qurt_sdflight_legacy.cmake
  11. 1
      platforms/posix/cmake/sitl_tests.cmake
  12. 73
      src/modules/uORB/uORBDevices.cpp
  13. 14
      src/modules/uORB/uORBDevices.hpp
  14. 35
      src/modules/uORB/uORBManager.cpp
  15. 37
      src/modules/uORB/uORBManager.hpp

2
cmake/configs/posix_eagle_hil.cmake

@ -17,6 +17,8 @@ else() @@ -17,6 +17,8 @@ else()
set(QC_SOC_TARGET "APQ8074")
endif()
add_definitions(-DORB_COMMUNICATOR)
set(config_module_list
drivers/linux_sbus

1
cmake/configs/posix_eagle_muorb.cmake

@ -4,6 +4,7 @@ set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolcha @@ -4,6 +4,7 @@ set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolcha
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PX4_SOURCE_DIR}/cmake/cmake_hexagon")
set(DISABLE_PARAMS_MODULE_SCOPING TRUE)
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/posix_sdflight_default.cmake

@ -28,6 +28,7 @@ else() @@ -28,6 +28,7 @@ else()
endif()
set(CONFIG_SHMEM "1")
add_definitions(-DORB_COMMUNICATOR)
set(config_module_list
drivers/blinkm

2
cmake/configs/posix_sdflight_legacy.cmake

@ -19,7 +19,7 @@ else() @@ -19,7 +19,7 @@ else()
endif()
set(CONFIG_SHMEM "1")
add_definitions(-DORB_COMMUNICATOR)
set(config_module_list
drivers/blinkm

1
cmake/configs/posix_sitl_default.cmake

@ -55,7 +55,6 @@ set(config_module_list @@ -55,7 +55,6 @@ set(config_module_list
platforms/posix/tests/hello
platforms/posix/tests/hrt_test
platforms/posix/tests/muorb
platforms/posix/tests/vcdev_test
#

1
cmake/configs/qurt_eagle_hil.cmake

@ -6,6 +6,7 @@ else() @@ -6,6 +6,7 @@ else()
endif()
set(DISABLE_PARAMS_MODULE_SCOPING TRUE)
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/qurt_eagle_muorb.cmake

@ -6,6 +6,7 @@ else() @@ -6,6 +6,7 @@ else()
endif()
set(DISABLE_PARAMS_MODULE_SCOPING TRUE)
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/qurt_eagle_travis.cmake

@ -11,6 +11,7 @@ else() @@ -11,6 +11,7 @@ else()
endif()
set(DISABLE_PARAMS_MODULE_SCOPING TRUE)
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/qurt_sdflight_default.cmake

@ -9,6 +9,7 @@ else() @@ -9,6 +9,7 @@ else()
endif()
set(CONFIG_SHMEM "1")
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/qurt_sdflight_legacy.cmake

@ -9,6 +9,7 @@ else() @@ -9,6 +9,7 @@ else()
endif()
set(CONFIG_SHMEM "1")
add_definitions(-DORB_COMMUNICATOR)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
platforms/posix/cmake/sitl_tests.cmake

@ -67,7 +67,6 @@ endforeach() @@ -67,7 +67,6 @@ endforeach()
set(test_cmds
hello
hrt_test
muorb_test
vcdev_test
wqueue_test
)

73
src/modules/uORB/uORBDevices.cpp

@ -63,7 +63,11 @@ @@ -63,7 +63,11 @@
#include "uORBDevices.hpp"
#include "uORBUtils.hpp"
#include "uORBManager.hpp"
#ifdef ORB_COMMUNICATOR
#include "uORBCommunicator.hpp"
#endif /* ORB_COMMUNICATOR */
#include <px4_sem.hpp>
#include <stdlib.h>
@ -85,14 +89,8 @@ uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const char *name, @@ -85,14 +89,8 @@ uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const char *name,
int priority, unsigned int queue_size) :
CDev(name, path),
_meta(meta),
_data(nullptr),
_last_update(0),
_generation(0),
_priority((uint8_t)priority),
_published(false),
_queue_size(queue_size),
_subscriber_count(0),
_publisher(0)
_queue_size(queue_size)
{
}
@ -163,7 +161,9 @@ uORB::DeviceNode::open(device::file_t *filp) @@ -163,7 +161,9 @@ uORB::DeviceNode::open(device::file_t *filp)
ret = CDev::open(filp);
#ifdef ORB_COMMUNICATOR
add_internal_subscriber();
#endif /* ORB_COMMUNICATOR */
if (ret != PX4_OK) {
PX4_ERR("CDev::open failed");
@ -196,7 +196,10 @@ uORB::DeviceNode::close(device::file_t *filp) @@ -196,7 +196,10 @@ uORB::DeviceNode::close(device::file_t *filp)
hrt_cancel(&sd->update_interval->update_call);
}
#ifdef ORB_COMMUNICATOR
remove_internal_subscriber();
#endif /* ORB_COMMUNICATOR */
delete sd;
sd = nullptr;
}
@ -454,6 +457,7 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v @@ -454,6 +457,7 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v
return PX4_ERROR;
}
#ifdef ORB_COMMUNICATOR
/*
* if the write is successful, send the data over the Multi-ORB link
*/
@ -466,6 +470,8 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v @@ -466,6 +470,8 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v
}
}
#endif /* ORB_COMMUNICATOR */
return PX4_OK;
}
@ -493,6 +499,7 @@ int uORB::DeviceNode::unadvertise(orb_advert_t handle) @@ -493,6 +499,7 @@ int uORB::DeviceNode::unadvertise(orb_advert_t handle)
return PX4_OK;
}
#ifdef ORB_COMMUNICATOR
int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, int priority)
{
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
@ -503,6 +510,7 @@ int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, int priorit @@ -503,6 +510,7 @@ int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, int priorit
return -1;
}
/*
//TODO: Check if we need this since we only unadvertise when things all shutdown and it doesn't actually remove the device
int16_t uORB::DeviceNode::topic_unadvertised(const orb_metadata *meta, int priority)
@ -514,6 +522,7 @@ int16_t uORB::DeviceNode::topic_unadvertised(const orb_metadata *meta, int prior @@ -514,6 +522,7 @@ int16_t uORB::DeviceNode::topic_unadvertised(const orb_metadata *meta, int prior
return -1;
}
*/
#endif /* ORB_COMMUNICATOR */
pollevent_t
uORB::DeviceNode::poll_state(device::file_t *filp)
@ -728,8 +737,7 @@ uORB::DeviceNode::print_statistics(bool reset) @@ -728,8 +737,7 @@ uORB::DeviceNode::print_statistics(bool reset)
return true;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
#ifdef ORB_COMMUNICATOR
void uORB::DeviceNode::add_internal_subscriber()
{
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
@ -746,8 +754,6 @@ void uORB::DeviceNode::add_internal_subscriber() @@ -746,8 +754,6 @@ void uORB::DeviceNode::add_internal_subscriber()
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void uORB::DeviceNode::remove_internal_subscriber()
{
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
@ -764,31 +770,6 @@ void uORB::DeviceNode::remove_internal_subscriber() @@ -764,31 +770,6 @@ void uORB::DeviceNode::remove_internal_subscriber()
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
bool uORB::DeviceNode::is_published()
{
return _published;
}
int uORB::DeviceNode::update_queue_size(unsigned int queue_size)
{
if (_queue_size == queue_size) {
return PX4_OK;
}
//queue size is limited to 255 for the single reason that we use uint8 to store it
if (_data || _queue_size > queue_size || queue_size > 255) {
return PX4_ERROR;
}
_queue_size = queue_size;
return PX4_OK;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::DeviceNode::process_add_subscription(int32_t rateInHz)
{
// if there is already data in the node, send this out to
@ -803,15 +784,11 @@ int16_t uORB::DeviceNode::process_add_subscription(int32_t rateInHz) @@ -803,15 +784,11 @@ int16_t uORB::DeviceNode::process_add_subscription(int32_t rateInHz)
return PX4_OK;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::DeviceNode::process_remove_subscription()
{
return PX4_OK;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data)
{
int16_t ret = -1;
@ -835,6 +812,22 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data @@ -835,6 +812,22 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data
return PX4_OK;
}
#endif /* ORB_COMMUNICATOR */
int uORB::DeviceNode::update_queue_size(unsigned int queue_size)
{
if (_queue_size == queue_size) {
return PX4_OK;
}
//queue size is limited to 255 for the single reason that we use uint8 to store it
if (_data || _queue_size > queue_size || queue_size > 255) {
return PX4_ERROR;
}
_queue_size = queue_size;
return PX4_OK;
}
uORB::DeviceMaster::DeviceMaster() :
CDev("obj_master", TOPIC_MASTER_DEVICE_PATH)

14
src/modules/uORB/uORBDevices.hpp

@ -116,6 +116,7 @@ public: @@ -116,6 +116,7 @@ public:
static int unadvertise(orb_advert_t handle);
#ifdef ORB_COMMUNICATOR
static int16_t topic_advertised(const orb_metadata *meta, int priority);
//static int16_t topic_unadvertised(const orb_metadata *meta, int priority);
@ -155,13 +156,14 @@ public: @@ -155,13 +156,14 @@ public:
* the Subscriber to be removed.
*/
void remove_internal_subscriber();
#endif /* ORB_COMMUNICATOR */
/**
* Return true if this topic has been published.
*
* This is used in the case of multi_pub/sub to check if it's valid to advertise
* and publish to this node or if another node should be tried. */
bool is_published();
bool is_published() const { return _published; }
/**
* Try to change the size of the queue. This can only be done as long as nobody published yet.
@ -214,13 +216,13 @@ private: @@ -214,13 +216,13 @@ private:
};
const struct orb_metadata *_meta; /**< object metadata information */
uint8_t *_data; /**< allocated object buffer */
hrt_abstime _last_update; /**< time the object was last updated */
volatile unsigned _generation; /**< object generation count */
uint8_t *_data{nullptr}; /**< allocated object buffer */
hrt_abstime _last_update{0}; /**< time the object was last updated */
volatile unsigned _generation{0}; /**< object generation count */
uint8_t _priority; /**< priority of the topic */
bool _published; /**< has ever data been published */
bool _published{false}; /**< has ever data been published */
uint8_t _queue_size; /**< maximum number of elements in the queue */
int16_t _subscriber_count;
int16_t _subscriber_count{0};
inline static SubscriberData *filp_to_sd(device::file_t *filp);

35
src/modules/uORB/uORBManager.cpp

@ -36,12 +36,13 @@ @@ -36,12 +36,13 @@
#include <stdarg.h>
#include <fcntl.h>
#include <errno.h>
#include <px4_config.h>
#include <px4_posix.h>
#include <px4_tasks.h>
#include "uORBUtils.hpp"
#include "uORBManager.hpp"
#include "px4_config.h"
#include "uORBDevices.hpp"
@ -62,10 +63,7 @@ bool uORB::Manager::initialize() @@ -62,10 +63,7 @@ bool uORB::Manager::initialize()
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
uORB::Manager::Manager()
: _comm_channel(nullptr)
{
_device_master = nullptr;
#ifdef ORB_USE_PUBLISHER_RULES
const char *file_name = "./rootfs/orb_publisher.rules";
int ret = readPublisherRulesFromFile(file_name, _publisher_rule);
@ -131,10 +129,14 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance) @@ -131,10 +129,14 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
#else
ret = px4_access(path, F_OK);
#ifdef ORB_COMMUNICATOR
if (ret == -1 && meta != nullptr && !_remote_topics.empty()) {
ret = (_remote_topics.find(meta->o_name) != _remote_topics.end()) ? OK : PX4_ERROR;
}
#endif /* ORB_COMMUNICATOR */
#endif
if (ret == 0) {
@ -215,8 +217,10 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, @@ -215,8 +217,10 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
return nullptr;
}
//For remote systems call over and inform them
#ifdef ORB_COMMUNICATOR
// For remote systems call over and inform them
uORB::DeviceNode::topic_advertised(meta, priority);
#endif /* ORB_COMMUNICATOR */
/* the advertiser must perform an initial publish to initialise the object */
result = orb_publish(meta, advertiser, data);
@ -318,13 +322,7 @@ int uORB::Manager::orb_get_interval(int handle, unsigned *interval) @@ -318,13 +322,7 @@ int uORB::Manager::orb_get_interval(int handle, unsigned *interval)
return ret;
}
int uORB::Manager::node_advertise
(
const struct orb_metadata *meta,
int *instance,
int priority
)
int uORB::Manager::node_advertise(const struct orb_metadata *meta, int *instance, int priority)
{
int fd = -1;
int ret = PX4_ERROR;
@ -441,8 +439,7 @@ int uORB::Manager::node_open(const struct orb_metadata *meta, const void *data, @@ -441,8 +439,7 @@ int uORB::Manager::node_open(const struct orb_metadata *meta, const void *data,
return fd;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
#ifdef ORB_COMMUNICATOR
void uORB::Manager::set_uorb_communicator(uORBCommunicator::IChannel *channel)
{
_comm_channel = channel;
@ -457,8 +454,6 @@ uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator() @@ -457,8 +454,6 @@ uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator()
return _comm_channel;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::Manager::process_remote_topic(const char *topic_name, bool isAdvertisement)
{
int16_t rc = 0;
@ -473,8 +468,6 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name, bool isAdver @@ -473,8 +468,6 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name, bool isAdver
return rc;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::Manager::process_add_subscription(const char *messageName, int32_t msgRateInHz)
{
PX4_DEBUG("entering Manager_process_add_subscription: name: %s", messageName);
@ -503,8 +496,6 @@ int16_t uORB::Manager::process_add_subscription(const char *messageName, int32_t @@ -503,8 +496,6 @@ int16_t uORB::Manager::process_add_subscription(const char *messageName, int32_t
return rc;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::Manager::process_remove_subscription(const char *messageName)
{
int16_t rc = -1;
@ -531,8 +522,6 @@ int16_t uORB::Manager::process_remove_subscription(const char *messageName) @@ -531,8 +522,6 @@ int16_t uORB::Manager::process_remove_subscription(const char *messageName)
return rc;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::Manager::process_received_message(const char *messageName, int32_t length, uint8_t *data)
{
int16_t rc = -1;
@ -565,7 +554,7 @@ bool uORB::Manager::is_remote_subscriber_present(const char *messageName) @@ -565,7 +554,7 @@ bool uORB::Manager::is_remote_subscriber_present(const char *messageName)
return (_remote_subscriber_topics.find(messageName) != _remote_subscriber_topics.end());
#endif
}
#endif /* ORB_COMMUNICATOR */
#ifdef ORB_USE_PUBLISHER_RULES

37
src/modules/uORB/uORBManager.hpp

@ -45,7 +45,9 @@ @@ -45,7 +45,9 @@
#define ORBSet std::set<std::string>
#endif
#ifdef ORB_COMMUNICATOR
#include "uORBCommunicator.hpp"
#endif /* ORB_COMMUNICATOR */
namespace uORB
{
@ -57,7 +59,10 @@ class Manager; @@ -57,7 +59,10 @@ class Manager;
* uORB nodes for each uORB topics and also implements the behavor of the
* uORB Api's.
*/
class uORB::Manager : public uORBCommunicator::IChannelRxHandler
class uORB::Manager
#ifdef ORB_COMMUNICATOR
: public uORBCommunicator::IChannelRxHandler
#endif /* ORB_COMMUNICATOR */
{
public:
// public interfaces for this class.
@ -73,10 +78,7 @@ public: @@ -73,10 +78,7 @@ public:
* Make sure initialize() is called first.
* @return uORB::Manager*
*/
static uORB::Manager *get_instance()
{
return _Instance;
}
static uORB::Manager *get_instance() { return _Instance; }
/**
* Get the DeviceMaster. If it does not exist,
@ -154,7 +156,6 @@ public: @@ -154,7 +156,6 @@ public:
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
int priority, unsigned int queue_size = 1);
/**
* Unadvertise a topic.
*
@ -350,6 +351,7 @@ public: @@ -350,6 +351,7 @@ public:
*/
int orb_get_interval(int handle, unsigned *interval);
#ifdef ORB_COMMUNICATOR
/**
* Method to set the uORBCommunicator::IChannel instance.
* @param comm_channel
@ -370,6 +372,7 @@ public: @@ -370,6 +372,7 @@ public:
* for a given topic
*/
bool is_remote_subscriber_present(const char *messageName);
#endif /* ORB_COMMUNICATOR */
private: // class methods
/**
@ -379,13 +382,7 @@ private: // class methods @@ -379,13 +382,7 @@ private: // class methods
* @todo verify that the existing node is the same as the one
* we tried to advertise.
*/
int
node_advertise
(
const struct orb_metadata *meta,
int *instance = nullptr,
int priority = ORB_PRIO_DEFAULT
);
int node_advertise(const struct orb_metadata *meta, int *instance = nullptr, int priority = ORB_PRIO_DEFAULT);
/**
* Common implementation for orb_advertise and orb_subscribe.
@ -398,11 +395,14 @@ private: // class methods @@ -398,11 +395,14 @@ private: // class methods
private: // data members
static Manager *_Instance;
#ifdef ORB_COMMUNICATOR
// the communicator channel instance.
uORBCommunicator::IChannel *_comm_channel;
uORBCommunicator::IChannel *_comm_channel{nullptr};
ORBSet _remote_subscriber_topics;
ORBSet _remote_topics;
#endif /* ORB_COMMUNICATOR */
DeviceMaster *_device_master{nullptr};
@ -410,6 +410,7 @@ private: //class methods @@ -410,6 +410,7 @@ private: //class methods
Manager();
~Manager();
#ifdef ORB_COMMUNICATOR
/**
* Interface to process a received topic from remote.
* @param topic_name
@ -436,8 +437,7 @@ private: //class methods @@ -436,8 +437,7 @@ private: //class methods
* handler.
* otherwise = failure.
*/
virtual int16_t process_add_subscription(const char *messageName,
int32_t msgRateInHz);
virtual int16_t process_add_subscription(const char *messageName, int32_t msgRateInHz);
/**
* Interface to process a received control msg to remove subscription
@ -465,9 +465,8 @@ private: //class methods @@ -465,9 +465,8 @@ private: //class methods
* handler.
* otherwise = failure.
*/
virtual int16_t process_received_message(const char *messageName,
int32_t length, uint8_t *data);
virtual int16_t process_received_message(const char *messageName, int32_t length, uint8_t *data);
#endif /* ORB_COMMUNICATOR */
#ifdef ORB_USE_PUBLISHER_RULES

Loading…
Cancel
Save