Browse Source

AP_HAL_PX4: remove left-overs of legacy UAVCAN support

master
Francisco Ferreira 8 years ago committed by Francisco Ferreira
parent
commit
965eda69f3
  1. 6
      libraries/AP_HAL_PX4/RCOutput.cpp
  2. 2
      libraries/AP_HAL_PX4/RCOutput.h

6
libraries/AP_HAL_PX4/RCOutput.cpp

@ -9,7 +9,6 @@ @@ -9,7 +9,6 @@
#include <unistd.h>
#include <drivers/drv_pwm_output.h>
#include <uORB/topics/actuator_direct.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_sbus.h>
@ -75,9 +74,6 @@ void PX4RCOutput::init() @@ -75,9 +74,6 @@ void PX4RCOutput::init()
for (uint8_t i=0; i < PX4_NUM_OUTPUT_CHANNELS; i++) {
_period[i] = PWM_IGNORE_THIS_CHANNEL;
}
// publish actuator vaules on demand
_actuator_direct_pub = nullptr;
}
@ -471,7 +467,7 @@ void PX4RCOutput::_send_outputs(void) @@ -471,7 +467,7 @@ void PX4RCOutput::_send_outputs(void)
}
if (to_send > 0) {
_arm_actuators(true);
::write(_pwm_fd, _period, to_send*sizeof(_period[0]));
}
if (_max_channel > _servo_count) {

2
libraries/AP_HAL_PX4/RCOutput.h

@ -62,13 +62,11 @@ private: @@ -62,13 +62,11 @@ private:
} _outputs[ORB_MULTI_MAX_INSTANCES] {};
actuator_armed_s _armed;
orb_advert_t _actuator_direct_pub;
orb_advert_t _actuator_armed_pub;
uint16_t _esc_pwm_min;
uint16_t _esc_pwm_max;
void _init_alt_channels(void);
void _publish_actuators(void);
void _arm_actuators(bool arm);
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask);
bool _corking;

Loading…
Cancel
Save