mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:55:34 +08:00
lib/rc: dsm_bind() add debug output for binding
- trivial code style cleanup
This commit is contained in:
@@ -39,7 +39,11 @@ add_library(rc
|
||||
dsm.cpp
|
||||
common_rc.cpp
|
||||
)
|
||||
target_compile_options(rc PRIVATE -Wno-unused-result)
|
||||
target_compile_options(rc
|
||||
PRIVATE
|
||||
#-DDEBUG_BUILD
|
||||
-Wno-unused-result
|
||||
)
|
||||
target_link_libraries(rc PRIVATE prebuild_targets)
|
||||
|
||||
if(PX4_TESTING AND (${PX4_PLATFORM} MATCHES "posix"))
|
||||
|
||||
+33
-35
@@ -164,8 +164,7 @@ static bool dsm_decode_channel(uint16_t raw, unsigned shift, uint8_t &channel, u
|
||||
*
|
||||
* @param[in] reset true=reset the 10/11 bit state to unknown
|
||||
*/
|
||||
static bool
|
||||
dsm_guess_format(bool reset)
|
||||
static bool dsm_guess_format(bool reset)
|
||||
{
|
||||
static uint32_t cs10 = 0;
|
||||
static uint32_t cs11 = 0;
|
||||
@@ -204,8 +203,7 @@ dsm_guess_format(bool reset)
|
||||
samples++;
|
||||
|
||||
#ifdef DSM_DEBUG
|
||||
printf("dsm guess format: samples: %d %s\n", samples,
|
||||
(reset) ? "RESET" : "");
|
||||
printf("dsm guess format: samples: %d %s\n", samples, (reset) ? "RESET" : "");
|
||||
#endif
|
||||
|
||||
/* wait until we have seen plenty of frames - 5 should normally be enough */
|
||||
@@ -269,8 +267,7 @@ dsm_guess_format(bool reset)
|
||||
return false;
|
||||
}
|
||||
|
||||
int
|
||||
dsm_config(int fd)
|
||||
int dsm_config(int fd)
|
||||
{
|
||||
#ifdef SPEKTRUM_POWER
|
||||
// enable power on DSM connector
|
||||
@@ -302,8 +299,7 @@ dsm_config(int fd)
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
dsm_proto_init()
|
||||
void dsm_proto_init()
|
||||
{
|
||||
dsm_channel_shift = 0;
|
||||
dsm_frame_drops = 0;
|
||||
@@ -322,10 +318,8 @@ dsm_proto_init()
|
||||
*
|
||||
* @param[in] device Device name of DSM UART
|
||||
*/
|
||||
int
|
||||
dsm_init(const char *device)
|
||||
int dsm_init(const char *device)
|
||||
{
|
||||
|
||||
if (dsm_fd < 0) {
|
||||
dsm_fd = open(device, O_RDWR | O_NONBLOCK);
|
||||
}
|
||||
@@ -342,8 +336,7 @@ dsm_init(const char *device)
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
dsm_deinit()
|
||||
void dsm_deinit()
|
||||
{
|
||||
if (dsm_fd >= 0) {
|
||||
close(dsm_fd);
|
||||
@@ -359,37 +352,44 @@ dsm_deinit()
|
||||
* @param[in] cmd commands - dsm_bind_power_down, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses, dsm_bind_reinit_uart
|
||||
* @param[in] pulses Number of pulses for dsm_bind_send_pulses command
|
||||
*/
|
||||
void
|
||||
dsm_bind(uint16_t cmd, int pulses)
|
||||
void dsm_bind(uint16_t cmd, int pulses)
|
||||
{
|
||||
if (dsm_fd < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (cmd) {
|
||||
|
||||
case DSM_CMD_BIND_POWER_DOWN:
|
||||
|
||||
/*power down DSM satellite*/
|
||||
// power down DSM satellite
|
||||
#if defined(DSM_DEBUG)
|
||||
printf("DSM: DSM_CMD_BIND_POWER_DOWN\n");
|
||||
#endif
|
||||
SPEKTRUM_POWER(false);
|
||||
break;
|
||||
|
||||
case DSM_CMD_BIND_POWER_UP:
|
||||
|
||||
/*power up DSM satellite*/
|
||||
// power up DSM satellite
|
||||
#if defined(DSM_DEBUG)
|
||||
printf("DSM: DSM_CMD_BIND_POWER_UP\n");
|
||||
#endif
|
||||
SPEKTRUM_POWER(true);
|
||||
dsm_guess_format(true);
|
||||
break;
|
||||
|
||||
case DSM_CMD_BIND_SET_RX_OUT:
|
||||
|
||||
/*Set UART RX pin to active output mode*/
|
||||
// Set UART RX pin to active output mode
|
||||
#if defined(DSM_DEBUG)
|
||||
printf("DSM: DSM_CMD_BIND_SET_RX_OUT\n");
|
||||
#endif
|
||||
SPEKTRUM_RX_AS_GPIO_OUTPUT();
|
||||
break;
|
||||
|
||||
case DSM_CMD_BIND_SEND_PULSES:
|
||||
// Pulse RX pin a number of times
|
||||
#if defined(DSM_DEBUG)
|
||||
printf("DSM: DSM_CMD_BIND_SEND_PULSES\n");
|
||||
#endif
|
||||
|
||||
/*Pulse RX pin a number of times*/
|
||||
for (int i = 0; i < pulses; i++) {
|
||||
dsm_udelay(120);
|
||||
SPEKTRUM_OUT(false);
|
||||
@@ -400,8 +400,10 @@ dsm_bind(uint16_t cmd, int pulses)
|
||||
break;
|
||||
|
||||
case DSM_CMD_BIND_REINIT_UART:
|
||||
|
||||
/*Restore USART RX pin to RS232 receive mode*/
|
||||
// Restore USART RX pin to RS232 receive mode
|
||||
#if defined(DSM_DEBUG)
|
||||
printf("DSM: DSM_CMD_BIND_REINIT_UART\n");
|
||||
#endif
|
||||
SPEKTRUM_RX_AS_UART();
|
||||
break;
|
||||
|
||||
@@ -417,9 +419,8 @@ dsm_bind(uint16_t cmd, int pulses)
|
||||
* @param[out] num_values pointer to number of raw channel values returned
|
||||
* @return true=DSM frame successfully decoded, false=no update
|
||||
*/
|
||||
bool
|
||||
dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, unsigned max_values,
|
||||
int8_t *rssi_percent)
|
||||
bool dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, unsigned max_values,
|
||||
int8_t *rssi_percent)
|
||||
{
|
||||
/*
|
||||
debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
|
||||
@@ -683,9 +684,8 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool
|
||||
* @param[out] rssi value in percent, if supported, or 127
|
||||
* @return true=decoded raw channel values updated, false=no update
|
||||
*/
|
||||
bool
|
||||
dsm_input(int fd, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, uint8_t *n_bytes, uint8_t **bytes,
|
||||
int8_t *rssi, unsigned max_values)
|
||||
bool dsm_input(int fd, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, uint8_t *n_bytes, uint8_t **bytes,
|
||||
int8_t *rssi, unsigned max_values)
|
||||
{
|
||||
/*
|
||||
* The S.BUS protocol doesn't provide reliable framing,
|
||||
@@ -726,11 +726,9 @@ dsm_input(int fd, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, uint
|
||||
return dsm_parse(now, &dsm_buf[0], ret, values, num_values, dsm_11_bit, &dsm_frame_drops, rssi, max_values);
|
||||
}
|
||||
|
||||
bool
|
||||
dsm_parse(const uint64_t now, const uint8_t *frame, const unsigned len, uint16_t *values,
|
||||
uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, int8_t *rssi_percent, uint16_t max_channels)
|
||||
bool dsm_parse(const uint64_t now, const uint8_t *frame, const unsigned len, uint16_t *values,
|
||||
uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, int8_t *rssi_percent, uint16_t max_channels)
|
||||
{
|
||||
|
||||
/* this is set by the decoding state machine and will default to false
|
||||
* once everything that was decodable has been decoded.
|
||||
*/
|
||||
|
||||
Reference in New Issue
Block a user