forked from Archive/PX4-Autopilot
commit
295e9d590e
|
@ -41,6 +41,7 @@
|
|||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
|
@ -64,6 +65,8 @@
|
|||
#include <systemlib/err.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
/*
|
||||
* Register accessors.
|
||||
* For now, no reason not to just use ADC1.
|
||||
|
@ -119,6 +122,8 @@ private:
|
|||
unsigned _channel_count;
|
||||
adc_msg_s *_samples; /**< sample buffer */
|
||||
|
||||
orb_advert_t _to_system_power;
|
||||
|
||||
/** work trampoline */
|
||||
static void _tick_trampoline(void *arg);
|
||||
|
||||
|
@ -134,13 +139,16 @@ private:
|
|||
*/
|
||||
uint16_t _sample(unsigned channel);
|
||||
|
||||
// update system_power ORB topic, only on FMUv2
|
||||
void update_system_power(void);
|
||||
};
|
||||
|
||||
ADC::ADC(uint32_t channels) :
|
||||
CDev("adc", ADC_DEVICE_PATH),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
|
||||
_channel_count(0),
|
||||
_samples(nullptr)
|
||||
_samples(nullptr),
|
||||
_to_system_power(0)
|
||||
{
|
||||
_debug_enabled = true;
|
||||
|
||||
|
@ -290,6 +298,43 @@ ADC::_tick()
|
|||
/* scan the channel set and sample each */
|
||||
for (unsigned i = 0; i < _channel_count; i++)
|
||||
_samples[i].am_data = _sample(_samples[i].am_channel);
|
||||
update_system_power();
|
||||
}
|
||||
|
||||
void
|
||||
ADC::update_system_power(void)
|
||||
{
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
system_power_s system_power;
|
||||
system_power.timestamp = hrt_absolute_time();
|
||||
|
||||
system_power.voltage5V_v = 0;
|
||||
for (unsigned i = 0; i < _channel_count; i++) {
|
||||
if (_samples[i].am_channel == 4) {
|
||||
// it is 2:1 scaled
|
||||
system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
|
||||
}
|
||||
}
|
||||
|
||||
// these are not ADC related, but it is convenient to
|
||||
// publish these to the same topic
|
||||
system_power.usb_connected = stm32_gpioread(GPIO_OTGFS_VBUS);
|
||||
|
||||
// note that the valid pins are active low
|
||||
system_power.brick_valid = !stm32_gpioread(GPIO_VDD_BRICK_VALID);
|
||||
system_power.servo_valid = !stm32_gpioread(GPIO_VDD_SERVO_VALID);
|
||||
|
||||
// OC pins are active low
|
||||
system_power.periph_5V_OC = !stm32_gpioread(GPIO_VDD_5V_PERIPH_OC);
|
||||
system_power.hipower_5V_OC = !stm32_gpioread(GPIO_VDD_5V_HIPOWER_OC);
|
||||
|
||||
/* lazily publish */
|
||||
if (_to_system_power > 0) {
|
||||
orb_publish(ORB_ID(system_power), _to_system_power, &system_power);
|
||||
} else {
|
||||
_to_system_power = orb_advertise(ORB_ID(system_power), &system_power);
|
||||
}
|
||||
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
}
|
||||
|
||||
uint16_t
|
||||
|
|
|
@ -84,6 +84,8 @@
|
|||
#include <uORB/topics/esc_status.h>
|
||||
#include <uORB/topics/telemetry_status.h>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
#include <uORB/topics/system_power.h>
|
||||
#include <uORB/topics/servorail_status.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
@ -796,6 +798,8 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
struct telemetry_status_s telemetry;
|
||||
struct range_finder_report range_finder;
|
||||
struct estimator_status_report estimator_status;
|
||||
struct system_power_s system_power;
|
||||
struct servorail_status_s servorail_status;
|
||||
} buf;
|
||||
|
||||
memset(&buf, 0, sizeof(buf));
|
||||
|
@ -828,6 +832,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
struct log_DIST_s log_DIST;
|
||||
struct log_TELE_s log_TELE;
|
||||
struct log_ESTM_s log_ESTM;
|
||||
struct log_PWR_s log_PWR;
|
||||
} body;
|
||||
} log_msg = {
|
||||
LOG_PACKET_HEADER_INIT(0)
|
||||
|
@ -859,6 +864,8 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
int telemetry_sub;
|
||||
int range_finder_sub;
|
||||
int estimator_status_sub;
|
||||
int system_power_sub;
|
||||
int servorail_status_sub;
|
||||
} subs;
|
||||
|
||||
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
|
||||
|
@ -884,6 +891,8 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
|
||||
subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
|
||||
subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status));
|
||||
subs.system_power_sub = orb_subscribe(ORB_ID(system_power));
|
||||
subs.servorail_status_sub = orb_subscribe(ORB_ID(servorail_status));
|
||||
|
||||
thread_running = true;
|
||||
|
||||
|
@ -1226,6 +1235,24 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
LOGBUFFER_WRITE_AND_COUNT(BATT);
|
||||
}
|
||||
|
||||
/* --- SYSTEM POWER RAILS --- */
|
||||
if (copy_if_updated(ORB_ID(system_power), subs.system_power_sub, &buf.system_power)) {
|
||||
log_msg.msg_type = LOG_PWR_MSG;
|
||||
log_msg.body.log_PWR.peripherals_5v = buf.system_power.voltage5V_v;
|
||||
log_msg.body.log_PWR.usb_ok = buf.system_power.usb_connected;
|
||||
log_msg.body.log_PWR.brick_ok = buf.system_power.brick_valid;
|
||||
log_msg.body.log_PWR.servo_ok = buf.system_power.servo_valid;
|
||||
log_msg.body.log_PWR.low_power_rail_overcurrent = buf.system_power.periph_5V_OC;
|
||||
log_msg.body.log_PWR.high_power_rail_overcurrent = buf.system_power.hipower_5V_OC;
|
||||
|
||||
/* copy servo rail status topic here too */
|
||||
orb_copy(ORB_ID(servorail_status), subs.servorail_status_sub, &buf.servorail_status);
|
||||
log_msg.body.log_PWR.servo_rail_5v = buf.servorail_status.voltage_v;
|
||||
log_msg.body.log_PWR.servo_rssi_5v = buf.servorail_status.rssi_v;
|
||||
|
||||
LOGBUFFER_WRITE_AND_COUNT(PWR);
|
||||
}
|
||||
|
||||
/* --- TELEMETRY --- */
|
||||
if (copy_if_updated(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry)) {
|
||||
log_msg.msg_type = LOG_TELE_MSG;
|
||||
|
|
|
@ -316,6 +316,19 @@ struct log_ESTM_s {
|
|||
// uint8_t kalman_gain_nan;
|
||||
// };
|
||||
|
||||
/* --- PWR - ONBOARD POWER SYSTEM --- */
|
||||
#define LOG_PWR_MSG 133
|
||||
struct log_PWR_s {
|
||||
float peripherals_5v;
|
||||
float servo_rail_5v;
|
||||
float servo_rssi_5v;
|
||||
uint8_t usb_ok;
|
||||
uint8_t brick_ok;
|
||||
uint8_t servo_ok;
|
||||
uint8_t low_power_rail_overcurrent;
|
||||
uint8_t high_power_rail_overcurrent;
|
||||
};
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
/* construct list of all message formats */
|
||||
|
@ -349,6 +362,7 @@ static const struct log_format_s log_formats[] = {
|
|||
LOG_FORMAT(VER, "NZ", "Arch,FwGit"),
|
||||
LOG_FORMAT(PARM, "Nf", "Name,Value"),
|
||||
LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,n_states,states_nan,cov_nan,kgain_nan"),
|
||||
LOG_FORMAT(PWR, "fffBBBBB", "5V_PERIPH, 5V_SRV,USB_OK,BRICK_OK,SRV_OK,PERIPH_OC,HIPWR_OC"),
|
||||
//LOG_FORMAT(ESTM, "ffffffffffffffffffffffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27,s28,s29,s30,s31,n_states,states_nan,cov_nan,kgain_nan"),
|
||||
};
|
||||
|
||||
|
|
|
@ -90,6 +90,9 @@ ORB_DEFINE(battery_status, struct battery_status_s);
|
|||
#include "topics/servorail_status.h"
|
||||
ORB_DEFINE(servorail_status, struct servorail_status_s);
|
||||
|
||||
#include "topics/system_power.h"
|
||||
ORB_DEFINE(system_power, struct system_power_s);
|
||||
|
||||
#include "topics/vehicle_global_position.h"
|
||||
ORB_DEFINE(vehicle_global_position, struct vehicle_global_position_s);
|
||||
|
||||
|
|
|
@ -0,0 +1,71 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012-2013 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file system_power.h
|
||||
*
|
||||
* Definition of the system_power voltage and power status uORB topic.
|
||||
*/
|
||||
|
||||
#ifndef SYSTEM_POWER_H_
|
||||
#define SYSTEM_POWER_H_
|
||||
|
||||
#include "../uORB.h"
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* voltage and power supply status
|
||||
*/
|
||||
struct system_power_s {
|
||||
uint64_t timestamp; /**< microseconds since system boot */
|
||||
float voltage5V_v; /**< peripheral 5V rail voltage */
|
||||
uint8_t usb_connected:1; /**< USB is connected when 1 */
|
||||
uint8_t brick_valid:1; /**< brick power is good when 1 */
|
||||
uint8_t servo_valid:1; /**< servo power is good when 1 */
|
||||
uint8_t periph_5V_OC:1; /**< peripheral overcurrent when 1 */
|
||||
uint8_t hipower_5V_OC:1; /**< hi power peripheral overcurrent when 1 */
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* register this as object request broker structure */
|
||||
ORB_DECLARE(system_power);
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue