Browse Source

drivers/rc_input: command line bind use vehicle_command

sbg
Daniel Agar 4 years ago
parent
commit
ddce711acb
  1. 13
      src/drivers/rc_input/RCInput.cpp
  2. 27
      src/drivers/rc_input/RCInput.hpp

13
src/drivers/rc_input/RCInput.cpp

@ -37,10 +37,6 @@ @@ -37,10 +37,6 @@
using namespace time_literals;
#if defined(SPEKTRUM_POWER)
static bool bind_spektrum(int arg = DSMX8_BIND_PULSES);
#endif /* SPEKTRUM_POWER */
constexpr char const *RCInput::RC_SCAN_STRING[];
RCInput::RCInput(const char *device) :
@ -606,7 +602,7 @@ void RCInput::Run() @@ -606,7 +602,7 @@ void RCInput::Run()
}
#if defined(SPEKTRUM_POWER)
bool bind_spektrum(int arg)
bool RCInput::bind_spektrum(int arg) const
{
int ret = PX4_ERROR;
@ -652,8 +648,11 @@ int RCInput::custom_command(int argc, char *argv[]) @@ -652,8 +648,11 @@ int RCInput::custom_command(int argc, char *argv[])
const char *verb = argv[0];
if (!strcmp(verb, "bind")) {
// TODO: publish vehicle_command
bind_spektrum();
uORB::PublicationQueued<vehicle_command_s> vehicle_command_pub{ORB_ID(vehicle_command)};
vehicle_command_s vcmd{};
vcmd.command = vehicle_command_s::VEHICLE_CMD_START_RX_PAIR;
vcmd.timestamp = hrt_absolute_time();
vehicle_command_pub.publish(vcmd);
return 0;
}

27
src/drivers/rc_input/RCInput.hpp

@ -85,8 +85,6 @@ public: @@ -85,8 +85,6 @@ public:
private:
void Run() override;
enum RC_SCAN {
RC_SCAN_PPM = 0,
RC_SCAN_SBUS,
@ -105,6 +103,21 @@ private: @@ -105,6 +103,21 @@ private:
"CRSF"
};
void Run() override;
#if defined(SPEKTRUM_POWER)
bool bind_spektrum(int arg = DSMX8_BIND_PULSES) const;
#endif // SPEKTRUM_POWER
void fill_rc_in(uint16_t raw_rc_count_local,
uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe,
unsigned frame_drops, int rssi);
void set_rc_scan_state(RC_SCAN _rc_scan_state);
void rc_io_invert(bool invert);
hrt_abstime _rc_scan_begin{0};
bool _initialized{false};
@ -135,14 +148,4 @@ private: @@ -135,14 +148,4 @@ private:
perf_counter_t _cycle_perf;
perf_counter_t _publish_interval_perf;
void fill_rc_in(uint16_t raw_rc_count_local,
uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe,
unsigned frame_drops, int rssi);
void set_rc_scan_state(RC_SCAN _rc_scan_state);
void rc_io_invert(bool invert);
};

Loading…
Cancel
Save