[pixhawk筆記]6-uORB流程及關鍵函數解析


本文中將結合代碼、文檔及注釋,給出uORB執行流程及關鍵函數的解析,由於uORB的機制實現較為復雜,所以本文主要學習如何使用uORB的接口來實現通信。回到上一篇筆記中的代碼:

#include <px4_config.h>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <string.h>

#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>

__EXPORT int px4_simple_app_main(int argc, char *argv[]);

int px4_simple_app_main(int argc, char *argv[])
{
    PX4_INFO("Hello Sky!");
    int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
        orb_set_interval(sensor_sub_fd,200);/* limit the update rate to 5 Hz */

    struct vehicle_attitude_s att;
    memset(&att,0,sizeof(att));
    orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude),&att);

    px4_pollfd_struct_t fds[] = {
        {.fd = sensor_sub_fd, .events = POLLIN},
    };        

    int error_counter = 0;

    for(int i=0;i<5;i++){
        int poll_ret = px4_poll(fds,1,1000);

        if(poll_ret == 0){
            PX4_ERR("Got no data within a second");
        }else if(poll_ret<0){
            if(error_counter<10 || error_counter % 50 == 0){
                PX4_ERR("ERROR return value from poll():%d",poll_ret);
            }

            error_counter++;
        }else{
            if(fds[0].revents & POLLIN){
                struct sensor_combined_s raw;
                orb_copy(ORB_ID(sensor_combined),sensor_sub_fd,&raw);
                PX4_INFO("Accelerometer:\t%8.4f\t%8.4f\t%8.4f",
                    (double)raw.accelerometer_m_s2[0],
                    (double)raw.accelerometer_m_s2[1],
                    (double)raw.accelerometer_m_s2[2]);

                att.rollspeed = raw.accelerometer_m_s2[0];
                att.pitchspeed = raw.accelerometer_m_s2[1];
                att.yawspeed = raw.accelerometer_m_s2[2];

                orb_publish(ORB_ID(vehicle_attitude),att_pub,&att);
            }
        }
    }
    PX4_INFO("exiting");
    return OK;
}
  • 訂閱
    可以看出,訂閱一個並獲取一個主題的信息主要流程及其中關鍵函數如下:
  • #include <uORB/topics/sensor_combined.h>
    ..
    int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));

  該語句先包含一個主題頭文件,該文件內容如下:

/****************************************************************************
 *
 *   Copyright (C) 2013-2016 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/* Auto-generated by genmsg_cpp from file /home/spy/src/Firmware/msg/sensor_combined.msg */


#pragma once

#include <stdint.h>
#ifdef __cplusplus
#include <cstring>
#else
#include <string.h>
#endif

#include <uORB/uORB.h>


#ifndef __cplusplus
#define RELATIVE_TIMESTAMP_INVALID 2147483647

#endif


#ifdef __cplusplus
struct __EXPORT sensor_combined_s {
#else
struct sensor_combined_s {
#endif
    uint64_t timestamp; // required for logger
    float gyro_rad[3];
    uint32_t gyro_integral_dt;
    int32_t accelerometer_timestamp_relative;
    float accelerometer_m_s2[3];
    uint32_t accelerometer_integral_dt;
    int32_t magnetometer_timestamp_relative;
    float magnetometer_ga[3];
    int32_t baro_timestamp_relative;
    float baro_alt_meter;
    float baro_temp_celcius;

#ifdef __cplusplus
    static constexpr int32_t RELATIVE_TIMESTAMP_INVALID = 2147483647;

#endif
};

/* register this as object request broker structure */
ORB_DECLARE(sensor_combined);

可以看出,該文件定義了一個sensor_combined的結構體,該結構體中包含了陀螺儀、加速度計、磁羅盤和氣壓計的數據。並使用ORB_DECLARE()宏聲明一個sensor_combined的主題。該文件由genmsg.cpp由/msg/sensor_combined.msg中的內容生成,該msg文件內容如下:

#
# Sensor readings in SI-unit form.
#
# These fields are scaled and offset-compensated where possible and do not
# change with board revisions and sensor updates.
#

int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid


# gyro timstamp is equal to the timestamp of the message
float32[3] gyro_rad			# average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period
uint32 gyro_integral_dt		# gyro measurement sampling period in us

int32 accelerometer_timestamp_relative	# timestamp + accelerometer_timestamp_relative = Accelerometer timestamp
float32[3] accelerometer_m_s2		# average value acceleration measured in the XYZ body frame in m/s/s over the last accelerometer sampling period
uint32 accelerometer_integral_dt	# accelerometer measurement sampling period in us

int32 magnetometer_timestamp_relative	# timestamp + magnetometer_timestamp_relative = Magnetometer timestamp
float32[3] magnetometer_ga		# Magnetic field in NED body frame, in Gauss

int32 baro_timestamp_relative		# timestamp + baro_timestamp_relative = Barometer timestamp
float32 baro_alt_meter			# Altitude, already temp. comp.
float32 baro_temp_celcius		# Temperature in degrees celsius

可以看出,在.msg文件中主要定義了一些成員變量項,自動生成的.h文件使用這些成員變量生成了結構體, 並使用ORB_DECLARE()宏聲明了這些主題,ORB_DECLARE()代碼如下:讀者也可以按該方法加入自定義的.msg文件,並編寫對應的CMakeLists.txt,來生成消息,通過uORB來交換數據。

/**
 * Declare (prototype) the uORB metadata for a topic (used by code generators).
 *
 * @param _name		The name of the topic.
 */
#if defined(__cplusplus)
# define ORB_DECLARE(_name)		extern "C" const struct orb_metadata __orb_##_name __EXPORT
#else
# define ORB_DECLARE(_name)		extern const struct orb_metadata __orb_##_name __EXPORT
#endif

可以看出,ORB_DECLARE()宏實際上定義了一些orb_metadata 的結構體變量,變量名為__orb_prototype_name。
訂閱時指定了ORB_ID,ORB_ID宏如下:

/**
 * Generates a pointer to the uORB metadata structure for
 * a given topic.
 *
 * The topic must have been declared previously in scope
 * with ORB_DECLARE().
 *
 * @param _name		The name of the topic.
 */
#define ORB_ID(_name)		&__orb_##_name

     其實是取了ORB_DECLARE()宏生成__orb_prototype_name結構體的地址。orb_subscribe的原型如下:

	/**
	 * Subscribe to a topic.
	 *
	 * The returned value is a file descriptor that can be passed to poll()
	 * in order to wait for updates to a topic, as well as topic_read,
	 * orb_check and orb_stat.
	 *
	 * Subscription will succeed even if the topic has not been advertised;
	 * in this case the topic will have a timestamp of zero, it will never
	 * signal a poll() event, checking will always return false and it cannot
	 * be copied. When the topic is subsequently advertised, poll, check,
	 * stat and copy calls will react to the initial publication that is
	 * performed as part of the advertisement.
	 *
	 * Subscription will fail if the topic is not known to the system, i.e.
	 * there is nothing in the system that has declared the topic and thus it
	 * can never be published.
	 *
	 * Internally this will call orb_subscribe_multi with instance 0.
	 *
	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
	 *      for the topic.
	 * @return    ERROR on error, otherwise returns a handle
	 *      that can be used to read and update the topic.
	 */
	int  orb_subscribe(const struct orb_metadata *meta) ;

可看出,其接受參數就是一個orb_metadata的常值指針,從注釋看,其返回一個int類型的fd,表示文件描述符,該描述符作為一個句柄,可以用來讀取並更新數據,如果訂閱失敗,則返回ERROR。
還有個orb_subscribe_multi函數可以用於訂閱主題有多個實例的情況:

	/**
	 * Subscribe to a multi-instance of a topic.
	 *
	 * The returned value is a file descriptor that can be passed to poll()
	 * in order to wait for updates to a topic, as well as topic_read,
	 * orb_check and orb_stat.
	 *
	 * Subscription will succeed even if the topic has not been advertised;
	 * in this case the topic will have a timestamp of zero, it will never
	 * signal a poll() event, checking will always return false and it cannot
	 * be copied. When the topic is subsequently advertised, poll, check,
	 * stat and copy calls will react to the initial publication that is
	 * performed as part of the advertisement.
	 *
	 * Subscription will fail if the topic is not known to the system, i.e.
	 * there is nothing in the system that has declared the topic and thus it
	 * can never be published.
	 *
	 * If a publisher publishes multiple instances the subscriber should
	 * subscribe to each instance with orb_subscribe_multi
	 * (@see orb_advertise_multi()).
	 *
	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
	 *      for the topic.
	 * @param instance  The instance of the topic. Instance 0 matches the
	 *      topic of the orb_subscribe() call, higher indices
	 *      are for topics created with orb_advertise_multi().
	 * @return    ERROR on error, otherwise returns a handle
	 *      that can be used to read and update the topic.
	 *      If the topic in question is not known (due to an
	 *      ORB_DEFINE_OPTIONAL with no corresponding ORB_DECLARE)
	 *      this function will return -1 and set errno to ENOENT.
	 */
	int  orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) ;

    該函數可以通過instance參數來指定實例索引。

訂閱了之后可以獲取該主題的數據,獲取主題數據有如下幾個函數可用:

      • px4_poll

本文開頭的代碼中即用的該函數,該函數其實是調用的nuttx系統的poll函數,該函數原型如下:

 
        
/****************************************************************************
 * Name: poll
 *
 * Description:
 *   poll() waits for one of a set of file descriptors to become ready to
 *   perform I/O.  If none of the events requested (and no error) has
 *   occurred for any of  the  file  descriptors,  then  poll() blocks until
 *   one of the events occurs.
 *
 * Inputs:
 *   fds  - List of structures describing file descriptors to be monitored
 *   nfds - The number of entries in the list
 *   timeout - Specifies an upper limit on the time for which poll() will
 *     block in milliseconds.  A negative value of timeout means an infinite
 *     timeout.
 *
 * Return:
 *   On success, the number of structures that have non-zero revents fields.
 *   A value of 0 indicates that the call timed out and no file descriptors
 *   were ready.  On error, -1 is returned, and errno is set appropriately:
 *
 *   EBADF  - An invalid file descriptor was given in one of the sets.
 *   EFAULT - The fds address is invalid
 *   EINTR  - A signal occurred before any requested event.
 *   EINVAL - The nfds value exceeds a system limit.
 *   ENOMEM - There was no space to allocate internal data structures.
 *   ENOSYS - One or more of the drivers supporting the file descriptor
 *     does not support the poll method.
 *
 ****************************************************************************/

int poll(FAR struct pollfd *fds, nfds_t nfds, int timeout)

可以看出,該函數用於阻塞等待文件描述符更新,等待時間為timeout毫秒。該函數返回值大於0表示等到數據更新,0表示沒有等到數據更新,小於0則表示發生錯誤。(返回值的詳細情況參見注釋)。

      • orb_check
        該函數原型及注釋如下:
        	/**
        	 * Check whether a topic has been published to since the last orb_copy.
        	 *
        	 * This check can be used to determine whether to copy the topic when
        	 * not using poll(), or to avoid the overhead of calling poll() when the
        	 * topic is likely to have updated.
        	 *
        	 * Updates are tracked on a per-handle basis; this call will continue to
        	 * return true until orb_copy is called using the same handle. This interface
        	 * should be preferred over calling orb_stat due to the race window between
        	 * stat and copy that can lead to missed updates.
        	 *
        	 * @param handle  A handle returned from orb_subscribe.
        	 * @param updated Set to true if the topic has been updated since the
        	 *      last time it was copied using this handle.
        	 * @return    OK if the check was successful, ERROR otherwise with
        	 *      errno set accordingly.
        	 */
        	int  orb_check(int handle, bool *updated) ;
        

        該函數也是用於檢查主題是否有更新,與px4_poll不同的是沒有阻塞等待,如果從上次orb_copy函數執行之后,主題發生了更新,則將第二個參數設置為true,否則為false。若函數正確執行,返回OK,否則返回ERROR。相比於px4_poll,該函數不會阻塞等待,所以不會造成系統過載。

      • orb_stat

        	/**
        	 * Return the last time that the topic was updated. If a queue is used, it returns
        	 * the timestamp of the latest element in the queue.
        	 *
        	 * @param handle  A handle returned from orb_subscribe.
        	 * @param time    Returns the absolute time that the topic was updated, or zero if it has
        	 *      never been updated. Time is measured in microseconds.
        	 * @return    OK on success, ERROR otherwise with errno set accordingly.
        	 */
        	int  orb_stat(int handle, uint64_t *time) ;
        

        該函數用於獲得指定的主題上一次更新的絕對時間,為毫秒數。返回值為OK表示成功執行,ERROR為有錯誤發生,具體錯誤可以查看errno。從orb_check的注釋中可以看出,該函數有缺陷,因為在orb_stat和orb_copy之間的時間窗口有可能發生更新,而根據返回的毫秒數來確定可能會錯過該更新。

         使用以上三個函數可以確定主題是否發生更新,如有更新發生,則可以使用orb_copy來從主題中獲得更新數據:

      • orb_copy
        該函數原型如下:
        	/**
        	 * Fetch data from a topic.
        	 *
        	 * This is the only operation that will reset the internal marker that
        	 * indicates that a topic has been updated for a subscriber. Once poll
        	 * or check return indicating that an updaet is available, this call
        	 * must be used to update the subscription.
        	 *
        	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
        	 *      for the topic.
        	 * @param handle  A handle returned from orb_subscribe.
        	 * @param buffer  Pointer to the buffer receiving the data, or NULL
        	 *      if the caller wants to clear the updated flag without
        	 *      using the data.
        	 * @return    OK on success, ERROR otherwise with errno set accordingly.
        	 */
        	int  orb_copy(const struct orb_metadata *meta, int handle, void *buffer) ;
        

        代碼中調用時形式如下:

         struct sensor_combined_s raw;
         orb_copy(ORB_ID(sensor_combined),sensor_sub_fd,&raw);
        

        第一個參數為ORB_ID獲取的主題ID(orb_metadata的指針),第二個參數為文件描述符,可用訂閱時返回值,第三個參數為更新數據的緩存地址,可以為一個主題對應結構體類型的地址。
        此外,在訂閱時還有其他函數:

      • orb_set_interval(sensor_sub_fd,200);該函數用於設置主題更新速率。

  • 發布
    發布主題主要使用兩個函數:
      • orb_advertise(ORB_ID(vehicle_attitude),&att);
        該函數原型及注釋如下:
        	// ==== uORB interface methods ====
        	/**
        	 * Advertise as the publisher of a topic.
        	 *
        	 * This performs the initial advertisement of a topic; it creates the topic
        	 * node in /obj if required and publishes the initial data.
        	 *
        	 * Any number of advertisers may publish to a topic; publications are atomic
        	 * but co-ordination between publishers is not provided by the ORB.
        	 *
        	 * Internally this will call orb_advertise_multi with an instance of 0 and
        	 * default priority.
        	 *
        	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
        	 *      for the topic.
        	 * @param data    A pointer to the initial data to be published.
        	 *      For topics updated by interrupt handlers, the advertisement
        	 *      must be performed from non-interrupt context.
        	 * @param queue_size  Maximum number of buffered elements. If this is 1, no queuing is
        	 *      used.
        	 * @return    nullptr on error, otherwise returns an object pointer
        	 *      that can be used to publish to the topic.
        	 *      If the topic in question is not known (due to an
        	 *      ORB_DEFINE with no corresponding ORB_DECLARE)
        	 *      this function will return nullptr and set errno to ENOENT.
        	 */
        	orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data, unsigned int queue_size = 1)
        	{
        		return orb_advertise_multi(meta, data, nullptr, ORB_PRIO_DEFAULT, queue_size);
        	}
        

        該函數用來廣播一個主題發布者,返回一個對象指針,該對象可用來發布主題,若出現錯誤,則返回空指針。
        該函數接收參數為有三個:第一個ORB_ID,表示要發布的主題ID;第二個為結構體指針,指向要發布的數據結構體;第三個為隊列大小,默認為1,表示沒有消息隊列。
        通過查看代碼,發現其實該函數調用了orb_advertise_multi函數,使用空指針0作為主題的實例索引,表示只廣播主題的第一個實例,並使用默認優先級來廣播。
        也可以使用orb_advertise_multi函數。其原型和注釋如下:

        /**
        	 * Advertise as the publisher of a topic.
        	 *
        	 * This performs the initial advertisement of a topic; it creates the topic
        	 * node in /obj if required and publishes the initial data.
        	 *
        	 * Any number of advertisers may publish to a topic; publications are atomic
        	 * but co-ordination between publishers is not provided by the ORB.
        	 *
        	 * The multi can be used to create multiple independent instances of the same topic
        	 * (each instance has its own buffer).
        	 * This is useful for multiple publishers who publish the same topic. The subscriber
        	 * then subscribes to all instances and chooses which source he wants to use.
        	 *
        	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
        	 *      for the topic.
        	 * @param data    A pointer to the initial data to be published.
        	 *      For topics updated by interrupt handlers, the advertisement
        	 *      must be performed from non-interrupt context.
        	 * @param instance  Pointer to an integer which will yield the instance ID (0-based)
        	 *      of the publication. This is an output parameter and will be set to the newly
        	 *      created instance, ie. 0 for the first advertiser, 1 for the next and so on.
        	 * @param priority  The priority of the instance. If a subscriber subscribes multiple
        	 *      instances, the priority allows the subscriber to prioritize the best
        	 *      data source as long as its available. The subscriber is responsible to check
        	 *      and handle different priorities (@see orb_priority()).
        	 * @param queue_size  Maximum number of buffered elements. If this is 1, no queuing is
        	 *      used.
        	 * @return    ERROR on error, otherwise returns a handle
        	 *      that can be used to publish to the topic.
        	 *      If the topic in question is not known (due to an
        	 *      ORB_DEFINE with no corresponding ORB_DECLARE)
        	 *      this function will return -1 and set errno to ENOENT.
        	 */
        	orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
        					 int priority, unsigned int queue_size = 1) ;
        

        該函數可以指定int*類型的instance參數,可以在一個主題存在多個實例時使用。

      • orb_publish(ORB_ID(vehicle_attitude),att_pub,&att);
        該函數用於在廣播主題之后發布主題,使用廣播時返回的主題句柄。函數原型及注釋如下:

        	/**
        	 * Publish new data to a topic.
        	 *
        	 * The data is atomically published to the topic and any waiting subscribers
        	 * will be notified.  Subscribers that are not waiting can check the topic
        	 * for updates using orb_check and/or orb_stat.
        	 *
        	 * @param meta    The uORB metadata (usually from the ORB_ID() macro)
        	 *      for the topic.
        	 * @handle    The handle returned from orb_advertise.
        	 * @param data    A pointer to the data to be published.
        	 * @return    OK on success, ERROR otherwise with errno set accordingly.
        	 */
        	int  orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) ;
        

        該函數用於發布主題,發布之后會通知所有訂閱者主題已更新(例如使用px4_poll進行阻塞等待的訂閱者),而orb_check需要手動檢查是否已更新。

         


免責聲明!

本站轉載的文章為個人學習借鑒使用,本站對版權不負任何法律責任。如果侵犯了您的隱私權益,請聯系本站郵箱yoyou2525@163.com刪除。



 
粵ICP備18138465號   © 2018-2025 CODEPRJ.COM