update uORB for generated topics

This commit is contained in:
Lorenz Meier 2015-07-12 12:35:29 +02:00
parent b3c1d56926
commit 9df860e921
5 changed files with 118 additions and 128 deletions

View File

@ -210,10 +210,7 @@ ORB_DEFINE(actuator_direct, struct actuator_direct_s);
ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
#include "topics/telemetry_status.h"
ORB_DEFINE(telemetry_status_0, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_1, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_2, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_3, struct telemetry_status_s);
ORB_DEFINE(telemetry_status, struct telemetry_status_s);
#include "topics/test_motor.h"
ORB_DEFINE(test_motor, struct test_motor_s);

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
* Copyright (C) 2013-2015 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
@ -31,31 +31,37 @@
*
****************************************************************************/
/**
* @file multirotor_motor_limits.h
*
* Definition of multirotor_motor_limits topic
*/
/* Auto-generated by genmsg_cpp from file /Users/lorenzmeier/src/Firmware/msg/multirotor_motor_limits.msg */
#ifndef MULTIROTOR_MOTOR_LIMITS_H_
#define MULTIROTOR_MOTOR_LIMITS_H_
#include "../uORB.h"
#pragma once
#include <stdint.h>
#include <uORB/uORB.h>
#ifndef __cplusplus
#endif
/**
* @addtogroup topics
* @{
*/
/**
* Motor limits
*/
#ifdef __cplusplus
struct __EXPORT multirotor_motor_limits_s {
#else
struct multirotor_motor_limits_s {
uint8_t lower_limit : 1; // at least one actuator command has saturated on the lower limit
uint8_t upper_limit : 1; // at least one actuator command has saturated on the upper limit
uint8_t yaw : 1; // yaw limit reached
uint8_t reserved : 5; // reserved
#endif
uint8_t lower_limit;
uint8_t upper_limit;
uint8_t yaw;
uint8_t reserved;
#ifdef __cplusplus
#endif
};
/**
@ -64,5 +70,3 @@ struct multirotor_motor_limits_s {
/* register this as object request broker structure */
ORB_DECLARE(multirotor_motor_limits);
#endif

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Copyright (C) 2013-2015 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
@ -31,27 +31,41 @@
*
****************************************************************************/
/**
* @file safety.h
*
* Safety topic to pass safety state from px4io driver to commander
* This concerns only the safety button of the px4io but has nothing to do
* with arming/disarming.
*/
/* Auto-generated by genmsg_cpp from file /Users/lorenzmeier/src/Firmware/msg/safety.msg */
#ifndef TOPIC_SAFETY_H
#define TOPIC_SAFETY_H
#pragma once
#include <stdint.h>
#include "../uORB.h"
#include <uORB/uORB.h>
#ifndef __cplusplus
#endif
/**
* @addtogroup topics
* @{
*/
#ifdef __cplusplus
struct __EXPORT safety_s {
#else
struct safety_s {
#endif
uint64_t timestamp;
bool safety_switch_available;
bool safety_off;
#ifdef __cplusplus
uint64_t timestamp;
bool safety_switch_available; /**< Set to true if a safety switch is connected */
bool safety_off; /**< Set to true if safety is off */
#endif
};
ORB_DECLARE(safety);
/**
* @}
*/
#endif
/* register this as object request broker structure */
ORB_DECLARE(safety);

View File

@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2014 PX4 Development Team. All rights reserved.
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* Copyright (C) 2013-2015 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
@ -34,50 +31,43 @@
*
****************************************************************************/
/**
* @file satellite_info.h
* Definition of the GNSS satellite info uORB topic.
*/
/* Auto-generated by genmsg_cpp from file /Users/lorenzmeier/src/Firmware/msg/satellite_info.msg */
#ifndef TOPIC_SAT_INFO_H_
#define TOPIC_SAT_INFO_H_
#pragma once
#include <stdint.h>
#include "../uORB.h"
#include <uORB/uORB.h>
#ifndef __cplusplus
#define SAT_INFO_MAX_SATELLITES 20
#endif
/**
* @addtogroup topics
* @{
*/
/**
* GNSS Satellite Info.
*/
#define SAT_INFO_MAX_SATELLITES 20
#ifdef __cplusplus
struct __EXPORT satellite_info_s {
#else
struct satellite_info_s {
uint64_t timestamp; /**< Timestamp of satellite info */
uint8_t count; /**< Number of satellites in satellite info */
uint8_t svid[SAT_INFO_MAX_SATELLITES]; /**< Space vehicle ID [1..255], see scheme below */
uint8_t used[SAT_INFO_MAX_SATELLITES]; /**< 0: Satellite not used, 1: used for navigation */
uint8_t elevation[SAT_INFO_MAX_SATELLITES]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
uint8_t azimuth[SAT_INFO_MAX_SATELLITES]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
uint8_t snr[SAT_INFO_MAX_SATELLITES]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
};
#endif
uint64_t timestamp;
uint8_t count;
uint8_t svid[20];
uint8_t used[20];
uint8_t elevation[20];
uint8_t azimuth[20];
uint8_t snr[20];
#ifdef __cplusplus
static const uint8_t SAT_INFO_MAX_SATELLITES = 20;
/**
* NAV_SVINFO space vehicle ID (svid) scheme according to u-blox protocol specs
* u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_(UBX-13003221).pdf
*
* GPS 1-32
* SBAS 120-158
* Galileo 211-246
* BeiDou 159-163, 33-64
* QZSS 193-197
* GLONASS 65-96, 255
*
*/
#endif
};
/**
* @}
@ -85,5 +75,3 @@ struct satellite_info_s {
/* register this as object request broker structure */
ORB_DECLARE(satellite_info);
#endif

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Copyright (C) 2013-2015 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
@ -31,72 +31,59 @@
*
****************************************************************************/
/**
* @file telemetry_status.h
*
* Telemetry status topics - radio status outputs
*/
/* Auto-generated by genmsg_cpp from file /Users/lorenzmeier/src/Firmware/msg/telemetry_status.msg */
#ifndef TOPIC_TELEMETRY_STATUS_H
#define TOPIC_TELEMETRY_STATUS_H
#pragma once
#include <stdint.h>
#include "../uORB.h"
#include <uORB/uORB.h>
enum TELEMETRY_STATUS_RADIO_TYPE {
TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
TELEMETRY_STATUS_RADIO_TYPE_WIRE
};
#ifndef __cplusplus
#define TELEMETRY_STATUS_RADIO_TYPE_GENERIC 0
#define TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO 1
#define TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET 2
#define TELEMETRY_STATUS_RADIO_TYPE_WIRE 3
#endif
/**
* @addtogroup topics
* @{
*/
#ifdef __cplusplus
struct __EXPORT telemetry_status_s {
#else
struct telemetry_status_s {
#endif
uint64_t timestamp;
uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */
uint64_t telem_time; /**< Time of last received telemetry status packet, 0 for none */
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
uint8_t rssi; /**< local signal strength */
uint8_t remote_rssi; /**< remote signal strength */
uint16_t rxerrors; /**< receive errors */
uint16_t fixed; /**< count of error corrected packets */
uint8_t noise; /**< background noise level */
uint8_t remote_noise; /**< remote background noise level */
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
uint8_t system_id; /**< system id of the remote system */
uint8_t component_id; /**< component id of the remote system */
uint64_t heartbeat_time;
uint64_t telem_time;
uint8_t type;
uint8_t rssi;
uint8_t remote_rssi;
uint16_t rxerrors;
uint16_t fixed;
uint8_t noise;
uint8_t remote_noise;
uint8_t txbuf;
uint8_t system_id;
uint8_t component_id;
#ifdef __cplusplus
static const uint8_t TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0;
static const uint8_t TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1;
static const uint8_t TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2;
static const uint8_t TELEMETRY_STATUS_RADIO_TYPE_WIRE = 3;
#endif
};
/**
* @}
*/
ORB_DECLARE(telemetry_status_0);
ORB_DECLARE(telemetry_status_1);
ORB_DECLARE(telemetry_status_2);
ORB_DECLARE(telemetry_status_3);
#define TELEMETRY_STATUS_ORB_ID_NUM 4
static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_ID_NUM] = {
ORB_ID(telemetry_status_0),
ORB_ID(telemetry_status_1),
ORB_ID(telemetry_status_2),
ORB_ID(telemetry_status_3),
};
// This is a hack to quiet an unused-variable warning for when telemetry_status.h is
// included but telemetry_status_orb_id is not referenced. The inline works if you
// choose to use it, but you can continue to just directly index into the array as well.
// If you don't use the inline this ends up being a no-op with no additional code emitted.
//static const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index);
static inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index)
{
return telemetry_status_orb_id[index];
}
#endif /* TOPIC_TELEMETRY_STATUS_H */
/* register this as object request broker structure */
ORB_DECLARE(telemetry_status);