PX4 Firmware
PX4 Autopilot Software http://px4.io
ocpoc_mmap.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "ocpoc_mmap.h"
35 
36 #include <px4_platform_common/log.h>
37 
38 #include <fcntl.h>
39 #include <sys/mman.h>
40 #include <unistd.h>
41 
42 using namespace linux_pwm_out;
43 
44 #define RCOUT_ZYNQ_PWM_BASE 0x43c00000
45 static const int TICK_PER_US = 50;
46 static const int FREQUENCY_PWM = 400;
47 static const int TICK_PER_S = 50000000;
48 
50 {
51  _num_outputs = max_num_outputs;
52 
54  PX4_WARN("number of outputs too large. Setting to %i", MAX_ZYNQ_PWMS);
56  }
57 }
58 
60 {
61  if (_shared_mem_cmd) {
62  munmap((void *)_shared_mem_cmd, 0x1000);
63  }
64 }
65 
66 unsigned long OcpocMmapPWMOut::freq2tick(uint16_t freq_hz)
67 {
68  unsigned long duty = TICK_PER_S / (unsigned long)freq_hz;
69  return duty;
70 }
71 
73 {
74  uint32_t mem_fd = open(_device, O_RDWR | O_SYNC);
75  _shared_mem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ | PROT_WRITE,
76  MAP_SHARED, mem_fd, RCOUT_ZYNQ_PWM_BASE);
77  close(mem_fd);
78 
79  if (_shared_mem_cmd == nullptr) {
80  PX4_ERR("initialize pwm pointer failed.");
81  return -1;
82  }
83 
84  for (int i = 0; i < _num_outputs; ++i) {
87  PX4_DEBUG("Output values: %d, %d", _shared_mem_cmd->periodhi[i].period, _shared_mem_cmd->periodhi[i].hi);
88  }
89 
90  return 0;
91 }
92 
93 int OcpocMmapPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
94 {
95  if (num_outputs > _num_outputs) {
96  num_outputs = _num_outputs;
97  }
98 
99  //convert this to duty_cycle in ns
100  for (int i = 0; i < num_outputs; ++i) {
101  //n = ::asprintf(&data, "%u", pwm[i] * 1000);
102  //::write(_pwm_fd[i], data, n);
103  _shared_mem_cmd->periodhi[i].hi = TICK_PER_US * pwm[i];
104  //printf("ch:%d, val:%d*%d ", ch, period_us, TICK_PER_US);
105  }
106 
107  return 0;
108 }
109 
struct s_period_hi periodhi[MAX_ZYNQ_PWMS]
Definition: ocpoc_mmap.h:67
static constexpr int MAX_ZYNQ_PWMS
maximum number of pwm channels
Definition: ocpoc_mmap.h:58
volatile struct pwm_cmd * _shared_mem_cmd
Definition: ocpoc_mmap.h:70
#define RCOUT_ZYNQ_PWM_BASE
Definition: ocpoc_mmap.cpp:44
static const int TICK_PER_US
Definition: ocpoc_mmap.cpp:45
OcpocMmapPWMOut(int max_num_outputs)
Definition: ocpoc_mmap.cpp:49
static unsigned long freq2tick(uint16_t freq_hz)
Definition: ocpoc_mmap.cpp:66
int send_output_pwm(const uint16_t *pwm, int num_outputs) override
Definition: ocpoc_mmap.cpp:93
static const int TICK_PER_S
Definition: ocpoc_mmap.cpp:47
static constexpr const char * _device
Definition: ocpoc_mmap.h:71
static const int FREQUENCY_PWM
Definition: ocpoc_mmap.cpp:46