APM:Libraries
AP_SBusOut.cpp
Go to the documentation of this file.
1 /*
2  * AP_SBusOut.cpp
3  *
4  * Created on: Aug 19, 2017
5  * Author: Mark Whitehorn
6  *
7  * method sbus1_out was ported from ardupilot/modules/PX4Firmware/src/lib/rc/sbus.c
8  * which has the following license:
9  *
10  * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions
14  * are met:
15  *
16  * 1. Redistributions of source code must retain the above copyright
17  * notice, this list of conditions and the following disclaimer.
18  * 2. Redistributions in binary form must reproduce the above copyright
19  * notice, this list of conditions and the following disclaimer in
20  * the documentation and/or other materials provided with the
21  * distribution.
22  * 3. Neither the name PX4 nor the names of its contributors may be
23  * used to endorse or promote products derived from this software
24  * without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
27  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
28  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
29  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
30  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
31  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
32  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
33  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
34  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
35  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
36  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
37  * POSSIBILITY OF SUCH DAMAGE.
38  *
39  */
40 #include "AP_SBusOut.h"
43 
44 extern const AP_HAL::HAL& hal;
45 
46 #define SBUS_DEBUG 0
47 
48 // SBUS1 constant definitions
49 // pulse widths measured using FrSky Sbus/PWM converter
50 #define SBUS_BSIZE 25
51 #define SBUS_CHANNELS 16
52 #define SBUS_MIN 880.0f
53 #define SBUS_MAX 2156.0f
54 #define SBUS_SCALE (2048.0f / (SBUS_MAX - SBUS_MIN))
55 
57  // @Param: RATE
58  // @DisplayName: SBUS default output rate
59  // @Description: This sets the SBUS output frame rate in Hz.
60  // @Range: 25 250
61  // @User: Advanced
62  // @Units: Hz
63  AP_GROUPINFO("RATE", 1, AP_SBusOut, sbus_rate, 50),
64 
66 };
67 
68 
69 // constructor
71 {
72  // set defaults from the parameter table
74 }
75 
76 
77 /*
78  * build and send sbus1 frame representing first 16 servo channels
79  * input arg is pointer to uart
80  */
81 void
83 {
84  if (!initialised) {
85  initialised = true;
86  init();
87  }
88 
89  if (sbus1_uart == nullptr) {
90  return;
91  }
92 
93  // constrain output rate using sbus_frame_interval
94  static uint32_t last_micros = 0;
95  uint32_t now = AP_HAL::micros();
96  if ((now - last_micros) > sbus_frame_interval) {
97  last_micros = now;
98  uint8_t buffer[SBUS_BSIZE] = { 0x0f }; // first byte is always 0x0f
99  uint8_t index = 1;
100  uint8_t offset = 0;
101  uint16_t value;
102 
103  /* construct sbus frame representing channels 1 through 16 (max) */
104  uint8_t nchan = MIN(NUM_SERVO_CHANNELS, SBUS_CHANNELS);
105  for (unsigned i = 0; i < nchan; ++i) {
107  if (ch == nullptr) {
108  continue;
109  }
110  /*protect from out of bounds values and limit to 11 bits*/
111  uint16_t pwmval = MAX(ch->get_output_pwm(), SBUS_MIN);
112  value = (uint16_t)((pwmval - SBUS_MIN) * SBUS_SCALE);
113  if (value > 0x07ff) {
114  value = 0x07ff;
115  }
116 
117 #if SBUS_DEBUG
118  static uint16_t lastch9 = 0;
119  if ((i==8) && (pwmval != lastch9)) {
120  lastch9 = pwmval;
121  hal.console->printf("channel 9 pwm: %04d\n", pwmval);
122  }
123 #endif
124 
125  while (offset >= 8) {
126  ++index;
127  offset -= 8;
128  }
129 
130  buffer[index] |= (value << (offset)) & 0xff;
131  buffer[index + 1] |= (value >> (8 - offset)) & 0xff;
132  buffer[index + 2] |= (value >> (16 - offset)) & 0xff;
133  offset += 11;
134  }
135 
136 #if SBUS_DEBUG
137  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
138  hal.gpio->write(55, 1);
139 #endif
140 
141  sbus1_uart->write(buffer, sizeof(buffer));
142 
143 #if SBUS_DEBUG
144  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
145  hal.gpio->write(55, 0);
146 #endif
147 
148  }
149 }
150 
152  uint16_t rate = sbus_rate.get();
153 
154 #if SBUS_DEBUG
155  hal.console->printf("AP_SBusOut: init %d Hz\n", rate);
156 #endif
157 
158  // subtract 500usec from requested frame interval to allow for latency
159  sbus_frame_interval = (1000UL * 1000UL) / rate - 500;
160  // at 100,000 bps, a 300 bit sbus frame takes 3msec to transfer
161  // require a minimum 700usec interframe gap
162  if (sbus_frame_interval < 3700) {
163  sbus_frame_interval = 3700;
164  }
165 
167  if (!serial_manager) {
168  return;
169  }
171 }
172 
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_HAL::UARTDriver * sbus1_uart
Definition: AP_SBusOut.h:27
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define SBUS_CHANNELS
Definition: AP_SBusOut.cpp:51
virtual void write(uint8_t pin, uint8_t value)=0
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void init(void)
Definition: AP_SBusOut.cpp:151
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_SBusOut.h:22
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual size_t write(uint8_t)=0
virtual void pinMode(uint8_t pin, uint8_t output)=0
#define SBUS_BSIZE
Definition: AP_SBusOut.cpp:50
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
static AP_SerialManager * get_instance(void)
uint16_t get_output_pwm(void) const
Definition: SRV_Channel.h:139
#define SBUS_SCALE
Definition: AP_SBusOut.cpp:54
void update()
Definition: AP_SBusOut.cpp:82
AP_HAL::GPIO * gpio
Definition: HAL.h:111
AP_Int16 sbus_rate
Definition: AP_SBusOut.h:33
float value
uint16_t sbus_frame_interval
Definition: AP_SBusOut.h:31
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
uint32_t micros()
Definition: system.cpp:152
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
bool initialised
Definition: AP_SBusOut.h:34
#define SBUS_MIN
Definition: AP_SBusOut.cpp:52