Move esc_status to generated topics

This commit is contained in:
Lorenz Meier 2015-05-25 19:14:48 +02:00
parent f7c9e918b1
commit e07731de7a
6 changed files with 37 additions and 123 deletions

11
msg/esc_report.msg Normal file
View File

@ -0,0 +1,11 @@
uint8 esc_vendor # Vendor of current ESC
uint32 esc_errorcount # Number of reported errors by ESC - if supported
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported
float32 esc_voltage # Voltage measured from current ESC [V] - if supported
float32 esc_current # Current measured from current ESC [A] - if supported
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported
float32 esc_setpoint # setpoint of current ESC
uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC)
uint16 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
uint16 esc_version # Version of current ESC - if supported
uint16 esc_state # State of ESC - depend on Vendor

19
msg/esc_status.msg Normal file
View File

@ -0,0 +1,19 @@
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs
uint8 ESC_VENDOR_GENERIC = 0 # generic ESC
uint8 ESC_VENDOR_MIKROKOPTER = 1 # Mikrokopter
uint8 ESC_VENDOR_GRAUPNER_HOTT = 2 # Graupner HoTT ESC
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC
uint8 ESC_CONNECTION_TYPE_ONESHOOT = 2 # One Shoot PPM
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus
uint16 counter # incremented by the writing thread everytime new data is stored
uint64 timestamp # in microseconds since system start, is set whenever the writing thread stores new data
uint8 esc_count # number of connected ESCs
uint8 esc_connectiontype # how ESCs connected to the system
esc_report[8] esc

View File

@ -111,9 +111,9 @@ publish_gam_message(const uint8_t *buffer)
// Publish it.
esc.timestamp = hrt_absolute_time();
esc.esc_count = 1;
esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_PPM;
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_vendor = esc_status_s::ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
esc.esc[0].esc_temperature = static_cast<float>(msg.temperature1) - 20.0F;
esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;

View File

@ -601,11 +601,11 @@ MK::task_main()
esc.counter++;
esc.timestamp = hrt_absolute_time();
esc.esc_count = (uint8_t) _num_outputs;
esc.esc_connectiontype = ESC_CONNECTION_TYPE_I2C;
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_I2C;
for (unsigned int i = 0; i < _num_outputs; i++) {
esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_vendor = esc_status_s::ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
esc.esc[i].esc_voltage = 0.0F;
esc.esc[i].esc_current = static_cast<float>(Motor[i].Current) * 0.1F;

View File

@ -1,116 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: @author Marco Bauer <marco@wtns.de>
*
* 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.
*
****************************************************************************/
/**
* @file esc_status.h
* Definition of the esc_status uORB topic.
*
* Published the state machine and the system status bitfields
* (see SYS_STATUS mavlink message), published only by commander app.
*
* All apps should write to subsystem_info:
*
* (any app) --> subsystem_info (published) --> (commander app state machine) --> esc_status --> (mavlink app)
*/
#ifndef ESC_STATUS_H_
#define ESC_STATUS_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
/**
* The number of ESCs supported.
* Current (Q2/2013) we support 8 ESCs,
*/
#define CONNECTED_ESC_MAX 8
enum ESC_VENDOR {
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
};
enum ESC_CONNECTION_TYPE {
ESC_CONNECTION_TYPE_PPM = 0, /**< Traditional PPM ESC */
ESC_CONNECTION_TYPE_SERIAL, /**< Serial Bus connected ESC */
ESC_CONNECTION_TYPE_ONESHOOT, /**< One Shoot PPM */
ESC_CONNECTION_TYPE_I2C, /**< I2C */
ESC_CONNECTION_TYPE_CAN /**< CAN-Bus */
};
/**
* @addtogroup topics
* @{
*/
/**
* Electronic speed controller status.
* Unsupported float fields should be assigned NaN.
*/
struct esc_status_s {
/* use of a counter and timestamp recommended (but not necessary) */
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
uint8_t esc_count; /**< number of connected ESCs */
enum ESC_CONNECTION_TYPE esc_connectiontype; /**< how ESCs connected to the system */
struct {
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */
uint32_t esc_errorcount; /**< Number of reported errors by ESC - if supported */
int32_t esc_rpm; /**< Motor RPM, negative for reverse rotation [RPM] - if supported */
float esc_voltage; /**< Voltage measured from current ESC [V] - if supported */
float esc_current; /**< Current measured from current ESC [A] - if supported */
float esc_temperature; /**< Temperature measured from current ESC [degC] - if supported */
float esc_setpoint; /**< setpoint of current ESC */
uint16_t esc_setpoint_raw; /**< setpoint of current ESC (Value sent to ESC) */
uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */
uint16_t esc_version; /**< Version of current ESC - if supported */
uint16_t esc_state; /**< State of ESC - depend on Vendor */
} esc[CONNECTED_ESC_MAX];
};
/**
* @}
*/
/* register this as object request broker structure */
//ORB_DECLARE(esc_status);
ORB_DECLARE_OPTIONAL(esc_status);
#endif

View File

@ -85,7 +85,7 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
{
if ((outputs == nullptr) ||
(num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize) ||
(num_outputs > CONNECTED_ESC_MAX)) {
(num_outputs > esc_status_s::CONNECTED_ESC_MAX)) {
perf_count(_perfcnt_invalid_input);
return;
}
@ -159,7 +159,7 @@ void UavcanEscController::arm_single_esc(int num, bool arm)
void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg)
{
if (msg.esc_index < CONNECTED_ESC_MAX) {
if (msg.esc_index < esc_status_s::CONNECTED_ESC_MAX) {
_esc_status.esc_count = uavcan::max<int>(_esc_status.esc_count, msg.esc_index + 1);
_esc_status.timestamp = msg.getMonotonicTimestamp().toUSec();
@ -179,7 +179,7 @@ void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<
void UavcanEscController::orb_pub_timer_cb(const uavcan::TimerEvent&)
{
_esc_status.counter += 1;
_esc_status.esc_connectiontype = ESC_CONNECTION_TYPE_CAN;
_esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_CAN;
if (_esc_status_pub > 0) {
(void)orb_publish(ORB_ID(esc_status), _esc_status_pub, &_esc_status);