mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
rc_input move to uORB::Subscription
This commit is contained in:
@@ -64,9 +64,6 @@ RCInput::~RCInput()
|
|||||||
{
|
{
|
||||||
orb_unadvertise(_to_input_rc);
|
orb_unadvertise(_to_input_rc);
|
||||||
|
|
||||||
orb_unsubscribe(_adc_sub);
|
|
||||||
orb_unsubscribe(_vehicle_cmd_sub);
|
|
||||||
|
|
||||||
#ifdef RC_SERIAL_PORT
|
#ifdef RC_SERIAL_PORT
|
||||||
dsm_deinit();
|
dsm_deinit();
|
||||||
#endif
|
#endif
|
||||||
@@ -82,15 +79,13 @@ RCInput::~RCInput()
|
|||||||
int
|
int
|
||||||
RCInput::init()
|
RCInput::init()
|
||||||
{
|
{
|
||||||
_adc_sub = orb_subscribe(ORB_ID(adc_report));
|
|
||||||
|
|
||||||
#ifdef RC_SERIAL_PORT
|
#ifdef RC_SERIAL_PORT
|
||||||
|
|
||||||
# ifdef RF_RADIO_POWER_CONTROL
|
# ifdef RF_RADIO_POWER_CONTROL
|
||||||
// power radio on
|
// power radio on
|
||||||
RF_RADIO_POWER_CONTROL(true);
|
RF_RADIO_POWER_CONTROL(true);
|
||||||
# endif
|
# endif
|
||||||
_vehicle_cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
|
|
||||||
// dsm_init sets some file static variables and returns a file descriptor
|
// dsm_init sets some file static variables and returns a file descriptor
|
||||||
_rcs_fd = dsm_init(RC_SERIAL_PORT);
|
_rcs_fd = dsm_init(RC_SERIAL_PORT);
|
||||||
// assume SBUS input and immediately switch it to
|
// assume SBUS input and immediately switch it to
|
||||||
@@ -297,13 +292,9 @@ RCInput::cycle()
|
|||||||
|
|
||||||
#if defined(SPEKTRUM_POWER)
|
#if defined(SPEKTRUM_POWER)
|
||||||
/* vehicle command */
|
/* vehicle command */
|
||||||
bool vehicle_command_updated = false;
|
vehicle_command_s vcmd;
|
||||||
orb_check(_vehicle_cmd_sub, &vehicle_command_updated);
|
|
||||||
|
|
||||||
if (vehicle_command_updated) {
|
|
||||||
vehicle_command_s vcmd = {};
|
|
||||||
orb_copy(ORB_ID(vehicle_command), _vehicle_cmd_sub, &vcmd);
|
|
||||||
|
|
||||||
|
if (_vehicle_cmd_sub.update(&vcmd)) {
|
||||||
// Check for a pairing command
|
// Check for a pairing command
|
||||||
if ((unsigned int)vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) {
|
if ((unsigned int)vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) {
|
||||||
if (!_rc_scan_locked /* !_armed.armed */) { // TODO: add armed check?
|
if (!_rc_scan_locked /* !_armed.armed */) { // TODO: add armed check?
|
||||||
@@ -336,13 +327,9 @@ RCInput::cycle()
|
|||||||
|
|
||||||
/* update ADC sampling */
|
/* update ADC sampling */
|
||||||
#ifdef ADC_RC_RSSI_CHANNEL
|
#ifdef ADC_RC_RSSI_CHANNEL
|
||||||
bool adc_updated = false;
|
adc_report_s adc;
|
||||||
orb_check(_adc_sub, &adc_updated);
|
|
||||||
|
|
||||||
if (adc_updated) {
|
if (_adc_sub.update(&adc)) {
|
||||||
|
|
||||||
struct adc_report_s adc;
|
|
||||||
orb_copy(ORB_ID(adc_report), _adc_sub, &adc);
|
|
||||||
const unsigned adc_chans = sizeof(adc.channel_id) / sizeof(adc.channel_id[0]);
|
const unsigned adc_chans = sizeof(adc.channel_id) / sizeof(adc.channel_id[0]);
|
||||||
|
|
||||||
for (unsigned i = 0; i < adc_chans; i++) {
|
for (unsigned i = 0; i < adc_chans; i++) {
|
||||||
|
|||||||
@@ -121,8 +121,8 @@ private:
|
|||||||
|
|
||||||
static struct work_s _work;
|
static struct work_s _work;
|
||||||
|
|
||||||
int _vehicle_cmd_sub{-1};
|
uORB::Subscription _vehicle_cmd_sub{ORB_ID(vehicle_command)};
|
||||||
int _adc_sub{-1};
|
uORB::Subscription _adc_sub{ORB_ID(adc_report)};
|
||||||
|
|
||||||
input_rc_s _rc_in{};
|
input_rc_s _rc_in{};
|
||||||
|
|
||||||
|
|||||||
@@ -34,23 +34,11 @@
|
|||||||
#include "crsf_telemetry.h"
|
#include "crsf_telemetry.h"
|
||||||
#include <lib/rc/crsf.h>
|
#include <lib/rc/crsf.h>
|
||||||
|
|
||||||
CRSFTelemetry::CRSFTelemetry(int uart_fd)
|
CRSFTelemetry::CRSFTelemetry(int uart_fd) :
|
||||||
: _vehicle_gps_position_sub(orb_subscribe(ORB_ID(vehicle_gps_position))),
|
_uart_fd(uart_fd)
|
||||||
_battery_status_sub(orb_subscribe(ORB_ID(battery_status))),
|
|
||||||
_vehicle_attitude_sub(orb_subscribe(ORB_ID(vehicle_attitude))),
|
|
||||||
_vehicle_status_sub(orb_subscribe(ORB_ID(vehicle_status))),
|
|
||||||
_uart_fd(uart_fd)
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
CRSFTelemetry::~CRSFTelemetry()
|
|
||||||
{
|
|
||||||
orb_unsubscribe(_vehicle_gps_position_sub);
|
|
||||||
orb_unsubscribe(_battery_status_sub);
|
|
||||||
orb_unsubscribe(_vehicle_attitude_sub);
|
|
||||||
orb_unsubscribe(_vehicle_status_sub);
|
|
||||||
}
|
|
||||||
|
|
||||||
bool CRSFTelemetry::update(const hrt_abstime &now)
|
bool CRSFTelemetry::update(const hrt_abstime &now)
|
||||||
{
|
{
|
||||||
const int update_rate_hz = 10;
|
const int update_rate_hz = 10;
|
||||||
@@ -89,7 +77,7 @@ bool CRSFTelemetry::send_battery()
|
|||||||
{
|
{
|
||||||
battery_status_s battery_status;
|
battery_status_s battery_status;
|
||||||
|
|
||||||
if (orb_copy(ORB_ID(battery_status), _battery_status_sub, &battery_status) != 0) {
|
if (!_battery_status_sub.update(&battery_status)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -104,7 +92,7 @@ bool CRSFTelemetry::send_gps()
|
|||||||
{
|
{
|
||||||
vehicle_gps_position_s vehicle_gps_position;
|
vehicle_gps_position_s vehicle_gps_position;
|
||||||
|
|
||||||
if (orb_copy(ORB_ID(vehicle_gps_position), _vehicle_gps_position_sub, &vehicle_gps_position) != 0) {
|
if (!_vehicle_gps_position_sub.update(&vehicle_gps_position)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -123,7 +111,7 @@ bool CRSFTelemetry::send_attitude()
|
|||||||
{
|
{
|
||||||
vehicle_attitude_s vehicle_attitude;
|
vehicle_attitude_s vehicle_attitude;
|
||||||
|
|
||||||
if (orb_copy(ORB_ID(vehicle_attitude), _vehicle_attitude_sub, &vehicle_attitude) != 0) {
|
if (!_vehicle_attitude_sub.update(&vehicle_attitude)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -138,7 +126,7 @@ bool CRSFTelemetry::send_flight_mode()
|
|||||||
{
|
{
|
||||||
vehicle_status_s vehicle_status;
|
vehicle_status_s vehicle_status;
|
||||||
|
|
||||||
if (orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &vehicle_status) != 0) {
|
if (!_vehicle_status_sub.update(&vehicle_status)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -39,6 +39,7 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <uORB/Subscription.hpp>
|
||||||
#include <uORB/topics/battery_status.h>
|
#include <uORB/topics/battery_status.h>
|
||||||
#include <uORB/topics/vehicle_attitude.h>
|
#include <uORB/topics/vehicle_attitude.h>
|
||||||
#include <uORB/topics/vehicle_gps_position.h>
|
#include <uORB/topics/vehicle_gps_position.h>
|
||||||
@@ -62,7 +63,7 @@ public:
|
|||||||
*/
|
*/
|
||||||
CRSFTelemetry(int uart_fd);
|
CRSFTelemetry(int uart_fd);
|
||||||
|
|
||||||
~CRSFTelemetry();
|
~CRSFTelemetry() = default;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Send telemetry data. Call this regularly (i.e. at 100Hz), it will automatically
|
* Send telemetry data. Call this regularly (i.e. at 100Hz), it will automatically
|
||||||
@@ -77,10 +78,10 @@ private:
|
|||||||
bool send_attitude();
|
bool send_attitude();
|
||||||
bool send_flight_mode();
|
bool send_flight_mode();
|
||||||
|
|
||||||
int _vehicle_gps_position_sub;
|
uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
|
||||||
int _battery_status_sub;
|
uORB::Subscription _battery_status_sub{ORB_ID(battery_status)};
|
||||||
int _vehicle_attitude_sub;
|
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
|
||||||
int _vehicle_status_sub;
|
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||||
|
|
||||||
hrt_abstime _last_update{0};
|
hrt_abstime _last_update{0};
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user