AP_HAL_SITL: RCOuput minor fix
correct style make constructor explicit use c++ cast
This commit is contained in:
parent
ff46964d22
commit
63b3618fc7
@ -2,12 +2,12 @@
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
#define ENABLE_DEBUG 0
|
#define ENABLE_DEBUG 0
|
||||||
|
|
||||||
#if ENABLE_DEBUG
|
#if ENABLE_DEBUG
|
||||||
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
# include <stdio.h>
|
||||||
|
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while (0)
|
||||||
#else
|
#else
|
||||||
# define Debug(fmt, args ...)
|
# define Debug(fmt, args ...)
|
||||||
#endif
|
#endif
|
||||||
@ -18,7 +18,7 @@ void RCOutput::init() {}
|
|||||||
|
|
||||||
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||||
{
|
{
|
||||||
Debug("set_freq(0x%04x, %u)\n", (unsigned)chmask, (unsigned)freq_hz);
|
Debug("set_freq(0x%04x, %u)\n", static_cast<uint32_t>(chmask), static_cast<uint32_t>(freq_hz));
|
||||||
_freq_hz = freq_hz;
|
_freq_hz = freq_hz;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -29,18 +29,18 @@ uint16_t RCOutput::get_freq(uint8_t ch)
|
|||||||
|
|
||||||
void RCOutput::enable_ch(uint8_t ch)
|
void RCOutput::enable_ch(uint8_t ch)
|
||||||
{
|
{
|
||||||
if (!(_enable_mask & (1U<<ch))) {
|
if (!(_enable_mask & (1U << ch))) {
|
||||||
Debug("enable_ch(%u)\n", ch);
|
Debug("enable_ch(%u)\n", ch);
|
||||||
}
|
}
|
||||||
_enable_mask |= 1U<<ch;
|
_enable_mask |= 1U << ch;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::disable_ch(uint8_t ch)
|
void RCOutput::disable_ch(uint8_t ch)
|
||||||
{
|
{
|
||||||
if (_enable_mask & (1U<<ch)) {
|
if (_enable_mask & (1U << ch)) {
|
||||||
Debug("disable_ch(%u)\n", ch);
|
Debug("disable_ch(%u)\n", ch);
|
||||||
}
|
}
|
||||||
_enable_mask &= ~1U<<ch;
|
_enable_mask &= ~1U << ch;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::write(uint8_t ch, uint16_t period_us)
|
void RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||||
@ -64,18 +64,18 @@ uint16_t RCOutput::read(uint8_t ch)
|
|||||||
|
|
||||||
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
||||||
{
|
{
|
||||||
memcpy(period_us, _sitlState->pwm_output, len*sizeof(uint16_t));
|
memcpy(period_us, _sitlState->pwm_output, len * sizeof(uint16_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::cork(void)
|
void RCOutput::cork(void)
|
||||||
{
|
{
|
||||||
memcpy(_pending, _sitlState->pwm_output, SITL_NUM_CHANNELS*sizeof(uint16_t));
|
memcpy(_pending, _sitlState->pwm_output, SITL_NUM_CHANNELS * sizeof(uint16_t));
|
||||||
_corked = true;
|
_corked = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::push(void)
|
void RCOutput::push(void)
|
||||||
{
|
{
|
||||||
memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS*sizeof(uint16_t));
|
memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
|
||||||
_corked = false;
|
_corked = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -6,20 +6,17 @@
|
|||||||
|
|
||||||
class HALSITL::RCOutput : public AP_HAL::RCOutput {
|
class HALSITL::RCOutput : public AP_HAL::RCOutput {
|
||||||
public:
|
public:
|
||||||
RCOutput(SITL_State *sitlState) {
|
explicit RCOutput(SITL_State *sitlState): _sitlState(sitlState), _freq_hz(50) {}
|
||||||
_sitlState = sitlState;
|
void init() override;
|
||||||
_freq_hz = 50;
|
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
||||||
}
|
|
||||||
void init() override;
|
|
||||||
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
|
||||||
uint16_t get_freq(uint8_t ch) override;
|
uint16_t get_freq(uint8_t ch) override;
|
||||||
void enable_ch(uint8_t ch) override;
|
void enable_ch(uint8_t ch) override;
|
||||||
void disable_ch(uint8_t ch) override;
|
void disable_ch(uint8_t ch) override;
|
||||||
void write(uint8_t ch, uint16_t period_us) override;
|
void write(uint8_t ch, uint16_t period_us) override;
|
||||||
uint16_t read(uint8_t ch) override;
|
uint16_t read(uint8_t ch) override;
|
||||||
void read(uint16_t* period_us, uint8_t len) override;
|
void read(uint16_t* period_us, uint8_t len) override;
|
||||||
void cork(void);
|
void cork(void);
|
||||||
void push(void);
|
void push(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SITL_State *_sitlState;
|
SITL_State *_sitlState;
|
||||||
|
Loading…
Reference in New Issue
Block a user