PX4 Firmware
PX4 Autopilot Software http://px4.io
sim_controller.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2015 PX4 Development Team. All rights reserved.
4  * Author: Pavel Kirienko <pavel.kirienko@gmail.com>
5  * David Sidrane<david_s5@nscdg.com>
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * 1. Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * 2. Redistributions in binary form must reproduce the above copyright
14  * notice, this list of conditions and the following disclaimer in
15  * the documentation and/or other materials provided with the
16  * distribution.
17  * 3. Neither the name PX4 nor the names of its contributors may be
18  * used to endorse or promote products derived from this software
19  * without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
28  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
29  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  ****************************************************************************/
35 #include <px4_platform_common/px4_config.h>
36 
37 #include <syslog.h>
38 
39 #include "sim_controller.hpp"
40 #include <uavcan/equipment/esc/RawCommand.hpp>
41 #include <uavcan/equipment/esc/RPMCommand.hpp>
42 #include <uavcan/equipment/esc/Status.hpp>
43 #include "led.hpp"
44 
45 
46 uavcan::Publisher<uavcan::equipment::esc::Status> *pub_status;
47 namespace
48 {
49 unsigned self_index = 0;
50 int rpm = 0;
51 
52 static void cb_raw_command(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::RawCommand> &msg)
53 {
54  if (msg.cmd.size() <= self_index) {
55  rgb_led(0, 0, 0, 0);
56  return;
57  }
58 
59  const float scaled = msg.cmd[self_index] / float(
61 
62  static int c = 0;
63 
64  if (c++ % 100 == 0) {
65  ::syslog(LOG_INFO, "scaled:%d\n", (int)scaled);
66  }
67 
68  if (scaled > 0) {
69  } else {
70  }
71 }
72 
73 static void cb_rpm_command(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::RPMCommand> &msg)
74 {
75  if (msg.rpm.size() <= self_index) {
76  return;
77  }
78 
79  rpm = msg.rpm[self_index];
80  static int c = 0;
81 
82  if (c++ % 100 == 0) {
83  ::syslog(LOG_INFO, "rpm:%d\n", rpm);
84  }
85 
86  if (rpm > 0) {
87  rgb_led(255, 0, 0, rpm);
88 
89  } else {
90  rgb_led(0, 0, 0, 0);
91  }
92 }
93 
94 void cb_10Hz(const uavcan::TimerEvent &event)
95 {
96  uavcan::equipment::esc::Status msg;
97 
98  msg.esc_index = self_index;
99  msg.rpm = rpm;
100  msg.voltage = 3.3F;
101  msg.current = 0.001F;
102  msg.temperature = 24.0F;
103  msg.power_rating_pct = static_cast<unsigned>(.5F * 100 + 0.5F);
104  msg.error_count = 0;
105 
106  if (rpm != 0) {
107  // Lower the publish rate to 1Hz if the motor is not running
108  static uavcan::MonotonicTime prev_pub_ts;
109 
110  if ((event.scheduled_time - prev_pub_ts).toMSec() >= 990) {
111  prev_pub_ts = event.scheduled_time;
112  pub_status->broadcast(msg);
113  }
114 
115  } else {
116  pub_status->broadcast(msg);
117  }
118 }
119 
120 }
121 int init_sim_controller(uavcan::INode &node)
122 {
123 
124  typedef void (*cb)(const uavcan::TimerEvent &);
125  static uavcan::Subscriber<uavcan::equipment::esc::RawCommand> sub_raw_command(node);
126  static uavcan::Subscriber<uavcan::equipment::esc::RPMCommand> sub_rpm_command(node);
127  static uavcan::TimerEventForwarder<cb> timer_10hz(node);
128 
129  self_index = 0;
130 
131  int res = 0;
132 
133  res = sub_raw_command.start(cb_raw_command);
134 
135  if (res != 0) {
136  return res;
137  }
138 
139  res = sub_rpm_command.start(cb_rpm_command);
140 
141  if (res != 0) {
142  return res;
143  }
144 
145  pub_status = new uavcan::Publisher<uavcan::equipment::esc::Status>(node);
146  res = pub_status->init();
147 
148  if (res != 0) {
149  return res;
150  }
151 
152  timer_10hz.setCallback(&cb_10Hz);
153  timer_10hz.startPeriodic(uavcan::MonotonicDuration::fromMSec(100));
154 
155  return 0;
156 }
uavcan::Publisher< uavcan::equipment::esc::Status > * pub_status
int init_sim_controller(uavcan::INode &node)
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
void rgb_led(int r, int g, int b, int freqs)
Definition: led.cpp:44