rc_ppm.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 
33 #include "rc_ppm.h"
34 
36 
38 {
39  // Initialize Variables
40  for (int i = 0; i < 8; i++)
41  rc_raw_[i] = 0;
42  chan_ = 0;
43  current_capture_ = 0;
44  last_capture_ = 0;
45  last_pulse_ms_ = 0;
46 
47  TIM_ = conf->TIM;
48  TIM_IT_ = conf->TIM_IT_CC;
49  TIM_Channel_ = conf->TIM_Channel;
50 
51  // Connect the global pointer
52  RC_PPM_Ptr = this;
53 
54  // Set up the Pin
55  pin_.init(conf->GPIO, conf->GPIO_Pin, GPIO::PERIPH_IN);
56 
57  // Connect Pin to the timer peripherial
58  GPIO_PinAFConfig(conf->GPIO, conf->GPIO_PinSource, conf->GIPO_AF_TIM);
59 
60  // Configure the timer
61  TIM_TimeBaseInitTypeDef TIM_init_struct;
62  TIM_init_struct.TIM_Period = 0xFFFF; // It'll get reset by the CC
63  TIM_init_struct.TIM_ClockDivision = TIM_CKD_DIV1; // No clock division
64  TIM_init_struct.TIM_Prescaler = (SystemCoreClock / (2000000)) - 1; // prescaler (0-indexed), set to 1 MHz
65  TIM_init_struct.TIM_CounterMode = TIM_CounterMode_Up; // count up
66  TIM_TimeBaseInit(TIM_, &TIM_init_struct);
67 
68  // Configure the Input Compare Peripheral
69  TIM_ICInitTypeDef TIM_IC_init_struct;
70  TIM_IC_init_struct.TIM_Channel = TIM_Channel_;
71  TIM_IC_init_struct.TIM_ICFilter = 0x00;
72  TIM_IC_init_struct.TIM_ICPolarity = TIM_ICPolarity_Rising;
73  TIM_IC_init_struct.TIM_ICPrescaler = TIM_ICPSC_DIV1;
74  TIM_IC_init_struct.TIM_ICSelection = TIM_ICSelection_DirectTI;
75  TIM_ICInit(TIM_, &TIM_IC_init_struct);
76 
77  // Set up the interrupt for the Timer
78  NVIC_InitTypeDef NVIC_InitStructure;
79  NVIC_InitStructure.NVIC_IRQChannel = conf->TIM_IRQn;
80  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x02;
81  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x01;
82  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
83  NVIC_Init(&NVIC_InitStructure);
84 
85  // Enable the CC interrupt
87 
88  // Start Counting!
91 }
92 
93 float RC_PPM::read(uint8_t channel)
94 {
95  return static_cast<float>(rc_raw_[channel] - 1000)/1000.0;
96 }
97 
99 {
100  return millis() > last_pulse_ms_ + 100;
101 }
102 
104 {
106  {
109 
110  switch (TIM_Channel_)
111  {
112  case TIM_Channel_1:
113  default:
115  break;
116  case TIM_Channel_2:
118  break;
119  case TIM_Channel_3:
121  break;
122  case TIM_Channel_4:
124  break;
125 
126  }
127  uint16_t diff = current_capture_ - last_capture_;
128  last_capture_ = current_capture_;
129 
130  // We're on a new frame
131  if (diff > 2500)
132  {
133  chan_ = 0;
134  }
135  else
136  {
137  // If it's a valid reading, then save it!
138  if (diff > 750 && diff < 2250 && chan_ < 8)
139  {
140  rc_raw_[chan_] = diff;
141  }
142  chan_++;
143  }
144  if (chan_ > 8)
145  {
146  chan_ = 0;
147  TIM_SetCounter(TIM_, 0);
148  }
149  }
150 }
151 
152 extern "C"
153 {
154 
155  void PPM_RC_IQRHandler(void)
156  {
157  if (RC_PPM_Ptr != NULL)
158  {
159  RC_PPM_Ptr->pulse_callback();
160  }
161  }
162 
163 }
uint16_t TIM_IT_
Definition: rc_ppm.h:48
uint32_t TIM_GetCapture3(TIM_TypeDef *TIMx)
Gets the TIMx Input Capture 3 value.
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
uint16_t TIM_IT_CC
Definition: system.h:102
uint16_t TIM_Channel_
Definition: rc_ppm.h:49
#define TIM_ICSelection_DirectTI
void TIM_ICInit(TIM_TypeDef *TIMx, TIM_ICInitTypeDef *TIM_ICInitStruct)
Initializes the TIM peripheral according to the specified parameters in the TIM_ICInitStruct.
uint32_t TIM_GetCapture1(TIM_TypeDef *TIMx)
Gets the TIMx Input Capture 1 value.
void TIM_TimeBaseInit(TIM_TypeDef *TIMx, TIM_TimeBaseInitTypeDef *TIM_TimeBaseInitStruct)
Initializes the TIMx Time Base Unit peripheral according to the specified parameters in the TIM_TimeB...
void init(const pwm_hardware_struct_t *conf)
Definition: rc_ppm.cpp:37
#define TIM_Channel_3
volatile uint32_t millis(void)
Definition: system.c:50
bool lost()
Definition: rc_ppm.cpp:98
void TIM_SetCounter(TIM_TypeDef *TIMx, uint32_t Counter)
Sets the TIMx Counter Register value.
uint16_t rc_raw_[8]
Definition: rc_ppm.h:44
uint16_t last_capture_
Definition: rc_ppm.h:43
ITStatus TIM_GetITStatus(TIM_TypeDef *TIMx, uint16_t TIM_IT)
Checks whether the TIM interrupt has occurred or not.
uint16_t current_capture_
Definition: rc_ppm.h:42
#define TIM_Channel_2
Definition: rc_ppm.h:37
uint32_t SystemCoreClock
void pulse_callback()
Definition: rc_ppm.cpp:103
uint16_t TIM_ICPolarity
#define TIM_Channel_4
IRQn_Type TIM_IRQn
Definition: system.h:101
uint32_t TIM_GetCapture2(TIM_TypeDef *TIMx)
Gets the TIMx Input Capture 2 value.
uint32_t last_pulse_ms_
Definition: rc_ppm.h:45
GPIO pin_
Definition: rc_ppm.h:40
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
Definition: gpio.cpp:34
uint16_t TIM_ICPrescaler
void TIM_Cmd(TIM_TypeDef *TIMx, FunctionalState NewState)
Enables or disables the specified TIM peripheral.
uint8_t chan_
Definition: rc_ppm.h:41
uint16_t GPIO_Pin
Definition: system.h:96
#define TIM_CKD_DIV1
TIM_TypeDef * TIM_
Definition: rc_ppm.h:47
void TIM_ARRPreloadConfig(TIM_TypeDef *TIMx, FunctionalState NewState)
Enables or disables TIMx peripheral Preload register on ARR.
uint32_t TIM_GetCapture4(TIM_TypeDef *TIMx)
Gets the TIMx Input Capture 4 value.
#define TIM_Channel_1
#define TIM_ICPolarity_Rising
TIM_TypeDef * TIM
Definition: system.h:98
TIM Time Base Init structure definition.
Definition: stm32f4xx_tim.h:55
#define TIM_ICPSC_DIV1
void TIM_ITConfig(TIM_TypeDef *TIMx, uint16_t TIM_IT, FunctionalState NewState)
Enables or disables the specified TIM interrupts.
TIM Input Capture Init structure definition.
uint16_t TIM_ICSelection
void PPM_RC_IQRHandler(void)
Definition: rc_ppm.cpp:155
uint8_t GPIO_PinSource
Definition: system.h:97
#define NULL
Definition: usbd_def.h:50
float read(uint8_t channel)
Definition: rc_ppm.cpp:93
uint8_t TIM_Channel
Definition: system.h:99
RC_PPM * RC_PPM_Ptr
Definition: rc_ppm.cpp:35
#define TIM_CounterMode_Up
void TIM_ClearITPendingBit(TIM_TypeDef *TIMx, uint16_t TIM_IT)
Clears the TIMx&#39;s interrupt pending bits.
uint8_t GIPO_AF_TIM
Definition: system.h:100
GPIO_TypeDef * GPIO
Definition: system.h:95


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:25