git-svn-id: https://arducopter.googlecode.com/svn/trunk@1287 f9c3cf11-9bcb-44bc-f272-b75c42450872
266 lines
30 KiB
HTML
266 lines
30 KiB
HTML
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
<html xmlns="http://www.w3.org/1999/xhtml">
|
|
<head>
|
|
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
<title>ArduPilot Libraries: /home/jgoppert/Projects/ap/libraries/RC_Channel/RC_Channel.cpp Source File</title>
|
|
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
<link href="doxygen.css" rel="stylesheet" type="text/css"/>
|
|
</head>
|
|
<body>
|
|
<!-- Generated by Doxygen 1.7.1 -->
|
|
<div class="navigation" id="top">
|
|
<div class="tabs">
|
|
<ul class="tablist">
|
|
<li><a href="main.html"><span>Main Page</span></a></li>
|
|
<li><a href="namespaces.html"><span>Namespaces</span></a></li>
|
|
<li><a href="annotated.html"><span>Classes</span></a></li>
|
|
<li class="current"><a href="files.html"><span>Files</span></a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="tabs2">
|
|
<ul class="tablist">
|
|
<li><a href="files.html"><span>File List</span></a></li>
|
|
<li><a href="globals.html"><span>File Members</span></a></li>
|
|
</ul>
|
|
</div>
|
|
<div class="header">
|
|
<div class="headertitle">
|
|
<h1>/home/jgoppert/Projects/ap/libraries/RC_Channel/RC_Channel.cpp</h1> </div>
|
|
</div>
|
|
<div class="contents">
|
|
<a href="_r_c___channel_8cpp.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*</span>
|
|
<a name="l00002"></a>00002 <span class="comment"> RC_Channel.cpp - Radio library for Arduino</span>
|
|
<a name="l00003"></a>00003 <span class="comment"> Code by Jason Short. DIYDrones.com</span>
|
|
<a name="l00004"></a>00004 <span class="comment"> </span>
|
|
<a name="l00005"></a>00005 <span class="comment"> This library is free software; you can redistribute it and / or</span>
|
|
<a name="l00006"></a>00006 <span class="comment"> modify it under the terms of the GNU Lesser General Public</span>
|
|
<a name="l00007"></a>00007 <span class="comment"> License as published by the Free Software Foundation; either</span>
|
|
<a name="l00008"></a>00008 <span class="comment"> version 2.1 of the License, or (at your option) any later version.</span>
|
|
<a name="l00009"></a>00009 <span class="comment"></span>
|
|
<a name="l00010"></a>00010 <span class="comment">*/</span>
|
|
<a name="l00011"></a>00011
|
|
<a name="l00012"></a>00012 <span class="preprocessor">#include <math.h></span>
|
|
<a name="l00013"></a>00013 <span class="preprocessor">#include <avr/eeprom.h></span>
|
|
<a name="l00014"></a>00014 <span class="preprocessor">#include "<a class="code" href="_w_program_8h.html">WProgram.h</a>"</span>
|
|
<a name="l00015"></a>00015 <span class="preprocessor">#include "<a class="code" href="_r_c___channel_8h.html" title="RC_Channel manager, with EEPROM-backed storage of constants.">RC_Channel.h</a>"</span>
|
|
<a name="l00016"></a>00016
|
|
<a name="l00017"></a><a class="code" href="_r_c___channel_8cpp.html#a8a7f485573c16394fc0792a66bd02c7a">00017</a> <span class="preprocessor">#define ANGLE 0</span>
|
|
<a name="l00018"></a><a class="code" href="_r_c___channel_8cpp.html#ac04dd0afaf7ea3eb2ade2544d2d5f907">00018</a> <span class="preprocessor"></span><span class="preprocessor">#define RANGE 1</span>
|
|
<a name="l00019"></a>00019 <span class="preprocessor"></span>
|
|
<a name="l00020"></a>00020 <span class="comment">// setup the control preferences</span>
|
|
<a name="l00021"></a>00021 <span class="keywordtype">void</span>
|
|
<a name="l00022"></a><a class="code" href="class_r_c___channel.html#adffafafffc9027e7293103766229b7e1">00022</a> <a class="code" href="class_r_c___channel.html#adffafafffc9027e7293103766229b7e1">RC_Channel::set_range</a>(<span class="keywordtype">int</span> low, <span class="keywordtype">int</span> high)
|
|
<a name="l00023"></a>00023 {
|
|
<a name="l00024"></a>00024 _type = RANGE;
|
|
<a name="l00025"></a>00025 _high = high;
|
|
<a name="l00026"></a>00026 _low = low;
|
|
<a name="l00027"></a>00027 }
|
|
<a name="l00028"></a>00028
|
|
<a name="l00029"></a>00029 <span class="keywordtype">void</span>
|
|
<a name="l00030"></a><a class="code" href="class_r_c___channel.html#ae528ed2a3460fddde82f114cb0694201">00030</a> <a class="code" href="class_r_c___channel.html#ae528ed2a3460fddde82f114cb0694201">RC_Channel::set_angle</a>(<span class="keywordtype">int</span> angle)
|
|
<a name="l00031"></a>00031 {
|
|
<a name="l00032"></a>00032 _type = ANGLE;
|
|
<a name="l00033"></a>00033 _high = angle;
|
|
<a name="l00034"></a>00034 }
|
|
<a name="l00035"></a>00035
|
|
<a name="l00036"></a>00036 <span class="keywordtype">void</span>
|
|
<a name="l00037"></a><a class="code" href="class_r_c___channel.html#a5b3740e7040f4b75d9cd591ebadca4c3">00037</a> <a class="code" href="class_r_c___channel.html#a5b3740e7040f4b75d9cd591ebadca4c3">RC_Channel::set_reverse</a>(<span class="keywordtype">bool</span> reverse)
|
|
<a name="l00038"></a>00038 {
|
|
<a name="l00039"></a>00039 <span class="keywordflow">if</span> (reverse) _reverse = -1;
|
|
<a name="l00040"></a>00040 <span class="keywordflow">else</span> _reverse = 1;
|
|
<a name="l00041"></a>00041 }
|
|
<a name="l00042"></a>00042
|
|
<a name="l00043"></a>00043 <span class="keywordtype">void</span>
|
|
<a name="l00044"></a><a class="code" href="class_r_c___channel.html#a045bff22457093d0c0fa78e19e618f9f">00044</a> <a class="code" href="class_r_c___channel.html#a045bff22457093d0c0fa78e19e618f9f">RC_Channel::set_filter</a>(<span class="keywordtype">bool</span> filter)
|
|
<a name="l00045"></a>00045 {
|
|
<a name="l00046"></a>00046 _filter = filter;
|
|
<a name="l00047"></a>00047 }
|
|
<a name="l00048"></a>00048
|
|
<a name="l00049"></a>00049 <span class="comment">// call after first read</span>
|
|
<a name="l00050"></a>00050 <span class="keywordtype">void</span>
|
|
<a name="l00051"></a><a class="code" href="class_r_c___channel.html#a8cf9c281ef6da9b275f5d682bb18904c">00051</a> <a class="code" href="class_r_c___channel.html#a8cf9c281ef6da9b275f5d682bb18904c">RC_Channel::trim</a>()
|
|
<a name="l00052"></a>00052 {
|
|
<a name="l00053"></a>00053 <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> = <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a>;
|
|
<a name="l00054"></a>00054
|
|
<a name="l00055"></a>00055 }
|
|
<a name="l00056"></a>00056
|
|
<a name="l00057"></a>00057 <span class="comment">// read input from APM_RC - create a control_in value</span>
|
|
<a name="l00058"></a>00058 <span class="keywordtype">void</span>
|
|
<a name="l00059"></a><a class="code" href="class_r_c___channel.html#aaa0d7cb0b9f9eb833cc46ac5f9192b86">00059</a> <a class="code" href="class_r_c___channel.html#aaa0d7cb0b9f9eb833cc46ac5f9192b86">RC_Channel::set_pwm</a>(<span class="keywordtype">int</span> pwm)
|
|
<a name="l00060"></a>00060 {
|
|
<a name="l00061"></a>00061 <span class="comment">//Serial.print(pwm,DEC);</span>
|
|
<a name="l00062"></a>00062
|
|
<a name="l00063"></a>00063 <span class="keywordflow">if</span>(_filter){
|
|
<a name="l00064"></a>00064 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> == 0)
|
|
<a name="l00065"></a>00065 <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> = pwm;
|
|
<a name="l00066"></a>00066 <span class="keywordflow">else</span>
|
|
<a name="l00067"></a>00067 <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> = ((pwm + <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a>) >> 1); <span class="comment">// Small filtering</span>
|
|
<a name="l00068"></a>00068 }<span class="keywordflow">else</span>{
|
|
<a name="l00069"></a>00069 <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> = pwm;
|
|
<a name="l00070"></a>00070 }
|
|
<a name="l00071"></a>00071
|
|
<a name="l00072"></a>00072 <span class="keywordflow">if</span>(_type == <a class="code" href="_r_c___channel_8cpp.html#ac04dd0afaf7ea3eb2ade2544d2d5f907">RANGE</a>){
|
|
<a name="l00073"></a>00073 <span class="comment">//Serial.print("range ");</span>
|
|
<a name="l00074"></a>00074 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> = <a class="code" href="class_r_c___channel.html#a10f764e7d9cb160b1da9ff286b8797fb">pwm_to_range</a>();
|
|
<a name="l00075"></a>00075 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> = (<a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> < <a class="code" href="class_r_c___channel.html#aad649dc43957d1c7d563fac50d5ed510">dead_zone</a>) ? 0 : <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a>;
|
|
<a name="l00076"></a>00076 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#afb3bb484e1f586d86105eb1bf40f8593">scale_output</a>){
|
|
<a name="l00077"></a>00077 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> *= <a class="code" href="class_r_c___channel.html#afb3bb484e1f586d86105eb1bf40f8593">scale_output</a>;
|
|
<a name="l00078"></a>00078 }
|
|
<a name="l00079"></a>00079
|
|
<a name="l00080"></a>00080 }<span class="keywordflow">else</span>{
|
|
<a name="l00081"></a>00081 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> = <a class="code" href="class_r_c___channel.html#a5a48b57daab9a0b5feac13af9c8b768d">pwm_to_angle</a>();
|
|
<a name="l00082"></a>00082 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> = (abs(<a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a>) < <a class="code" href="class_r_c___channel.html#aad649dc43957d1c7d563fac50d5ed510">dead_zone</a>) ? 0 : <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a>;
|
|
<a name="l00083"></a>00083 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#afb3bb484e1f586d86105eb1bf40f8593">scale_output</a>){
|
|
<a name="l00084"></a>00084 <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> *= <a class="code" href="class_r_c___channel.html#afb3bb484e1f586d86105eb1bf40f8593">scale_output</a>;
|
|
<a name="l00085"></a>00085 }
|
|
<a name="l00086"></a>00086 }
|
|
<a name="l00087"></a>00087 }
|
|
<a name="l00088"></a>00088
|
|
<a name="l00089"></a>00089 <span class="keywordtype">int</span>
|
|
<a name="l00090"></a><a class="code" href="class_r_c___channel.html#a8c8933633ace2ad8bfc3a91375f58169">00090</a> <a class="code" href="class_r_c___channel.html#a8c8933633ace2ad8bfc3a91375f58169">RC_Channel::control_mix</a>(<span class="keywordtype">float</span> value)
|
|
<a name="l00091"></a>00091 {
|
|
<a name="l00092"></a>00092 <span class="keywordflow">return</span> (1 - abs(<a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a> / _high)) * value + <a class="code" href="class_r_c___channel.html#aecc4c9d01e139561076e897af1286c0b">control_in</a>;
|
|
<a name="l00093"></a>00093 }
|
|
<a name="l00094"></a>00094
|
|
<a name="l00095"></a>00095 <span class="comment">// are we below a threshold?</span>
|
|
<a name="l00096"></a>00096 <span class="keywordtype">bool</span>
|
|
<a name="l00097"></a><a class="code" href="class_r_c___channel.html#a8e699f35b6c0e2524487c93cdef56ba9">00097</a> <a class="code" href="class_r_c___channel.html#a8e699f35b6c0e2524487c93cdef56ba9">RC_Channel::get_failsafe</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00098"></a>00098 {
|
|
<a name="l00099"></a>00099 <span class="keywordflow">return</span> (<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> < (<a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a> - 50));
|
|
<a name="l00100"></a>00100 }
|
|
<a name="l00101"></a>00101
|
|
<a name="l00102"></a>00102 <span class="comment">// returns just the PWM without the offset from radio_min</span>
|
|
<a name="l00103"></a>00103 <span class="keywordtype">void</span>
|
|
<a name="l00104"></a><a class="code" href="class_r_c___channel.html#a5876259d8fb8c1c475322a236bae7819">00104</a> <a class="code" href="class_r_c___channel.html#a5876259d8fb8c1c475322a236bae7819">RC_Channel::calc_pwm</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00105"></a>00105 {
|
|
<a name="l00106"></a>00106
|
|
<a name="l00107"></a>00107 <span class="keywordflow">if</span>(_type == <a class="code" href="_r_c___channel_8cpp.html#ac04dd0afaf7ea3eb2ade2544d2d5f907">RANGE</a>){
|
|
<a name="l00108"></a>00108 <a class="code" href="class_r_c___channel.html#ae8a2a575ae23099703ee2206a98017f4">pwm_out</a> = <a class="code" href="class_r_c___channel.html#ac50875b55ac524f9d0b2ee50174bd300">range_to_pwm</a>();
|
|
<a name="l00109"></a>00109 }<span class="keywordflow">else</span>{
|
|
<a name="l00110"></a>00110 <a class="code" href="class_r_c___channel.html#ae8a2a575ae23099703ee2206a98017f4">pwm_out</a> = <a class="code" href="class_r_c___channel.html#abcf4a69f7323c85306e8a25b34e929b3">angle_to_pwm</a>();
|
|
<a name="l00111"></a>00111 }
|
|
<a name="l00112"></a>00112 <span class="comment">//if(scale_output){</span>
|
|
<a name="l00113"></a>00113 <span class="comment">// pwm_out *= scale_output;</span>
|
|
<a name="l00114"></a>00114 <span class="comment">//}</span>
|
|
<a name="l00115"></a>00115 <a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a> = <a class="code" href="class_r_c___channel.html#ae8a2a575ae23099703ee2206a98017f4">pwm_out</a> + <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>;
|
|
<a name="l00116"></a>00116 <a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a> = constrain(<a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a>,radio_min, <a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a>);
|
|
<a name="l00117"></a>00117 }
|
|
<a name="l00118"></a>00118
|
|
<a name="l00119"></a>00119 <span class="comment">// ------------------------------------------</span>
|
|
<a name="l00120"></a>00120
|
|
<a name="l00121"></a>00121 <span class="keywordtype">void</span>
|
|
<a name="l00122"></a><a class="code" href="class_r_c___channel.html#a56117fe9f697096605f84a6045aaa935">00122</a> <a class="code" href="class_r_c___channel.html#a56117fe9f697096605f84a6045aaa935">RC_Channel::load_eeprom</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00123"></a>00123 {
|
|
<a name="l00124"></a>00124 <span class="comment">//radio_min = eeprom_read_word((uint16_t *) _address);</span>
|
|
<a name="l00125"></a>00125 <span class="comment">//radio_max = eeprom_read_word((uint16_t *) (_address + 2));</span>
|
|
<a name="l00126"></a>00126 <span class="comment">//radio_trim = eeprom_read_word((uint16_t *) (_address + 4));</span>
|
|
<a name="l00127"></a>00127 <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a> = _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#ab705d4b2d44f7d4c27bb1a382e783885">read_int</a>(_address);
|
|
<a name="l00128"></a>00128 <a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> = _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#ab705d4b2d44f7d4c27bb1a382e783885">read_int</a>(_address + 2);
|
|
<a name="l00129"></a>00129 <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> = _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#ab705d4b2d44f7d4c27bb1a382e783885">read_int</a>(_address + 4);
|
|
<a name="l00130"></a>00130 }
|
|
<a name="l00131"></a>00131
|
|
<a name="l00132"></a>00132 <span class="keywordtype">void</span>
|
|
<a name="l00133"></a><a class="code" href="class_r_c___channel.html#aae26f7c9f60cc08537fffe967510f481">00133</a> <a class="code" href="class_r_c___channel.html#aae26f7c9f60cc08537fffe967510f481">RC_Channel::save_eeprom</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00134"></a>00134 {
|
|
<a name="l00135"></a>00135 <span class="comment">//eeprom_write_word((uint16_t *) _address, radio_min);</span>
|
|
<a name="l00136"></a>00136 <span class="comment">//eeprom_write_word((uint16_t *) (_address + 2), radio_max);</span>
|
|
<a name="l00137"></a>00137 <span class="comment">//eeprom_write_word((uint16_t *) (_address + 4), radio_trim);</span>
|
|
<a name="l00138"></a>00138
|
|
<a name="l00139"></a>00139 _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#a76a66afde2196114cc4fc1b30faea0e7">write_int</a>(_address, <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>);
|
|
<a name="l00140"></a>00140 _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#a76a66afde2196114cc4fc1b30faea0e7">write_int</a>((_address + 2), <a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a>);
|
|
<a name="l00141"></a>00141 _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#a76a66afde2196114cc4fc1b30faea0e7">write_int</a>((_address + 4), <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>);
|
|
<a name="l00142"></a>00142 }
|
|
<a name="l00143"></a>00143
|
|
<a name="l00144"></a>00144 <span class="comment">// ------------------------------------------</span>
|
|
<a name="l00145"></a>00145 <span class="keywordtype">void</span>
|
|
<a name="l00146"></a><a class="code" href="class_r_c___channel.html#afed2cdb2de5fd66cb6eae528e5b6344a">00146</a> <a class="code" href="class_r_c___channel.html#afed2cdb2de5fd66cb6eae528e5b6344a">RC_Channel::save_trim</a>(<span class="keywordtype">void</span>)
|
|
<a name="l00147"></a>00147 {
|
|
<a name="l00148"></a>00148 <span class="comment">//eeprom_write_word((uint16_t *) (_address + 4), radio_trim);</span>
|
|
<a name="l00149"></a>00149 _ee.<a class="code" href="class_a_p___e_e_p_r_o_m_b.html#a76a66afde2196114cc4fc1b30faea0e7">write_int</a>((_address + 4), <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>);
|
|
<a name="l00150"></a>00150 }
|
|
<a name="l00151"></a>00151
|
|
<a name="l00152"></a>00152 <span class="comment">// ------------------------------------------</span>
|
|
<a name="l00153"></a>00153
|
|
<a name="l00154"></a>00154 <span class="keywordtype">void</span>
|
|
<a name="l00155"></a><a class="code" href="class_r_c___channel.html#ad9ea651815e47c12203d4f9cfe32abfd">00155</a> <a class="code" href="class_r_c___channel.html#ad9ea651815e47c12203d4f9cfe32abfd">RC_Channel::zero_min_max</a>()
|
|
<a name="l00156"></a>00156 {
|
|
<a name="l00157"></a>00157 <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a> = <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a> = <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a>;
|
|
<a name="l00158"></a>00158 }
|
|
<a name="l00159"></a>00159
|
|
<a name="l00160"></a>00160 <span class="keywordtype">void</span>
|
|
<a name="l00161"></a><a class="code" href="class_r_c___channel.html#a148e078784162a8823f190be7bd9bada">00161</a> <a class="code" href="class_r_c___channel.html#a148e078784162a8823f190be7bd9bada">RC_Channel::update_min_max</a>()
|
|
<a name="l00162"></a>00162 {
|
|
<a name="l00163"></a>00163 <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a> = min(<a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>, <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a>);
|
|
<a name="l00164"></a>00164 <a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> = max(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a>, <a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a>);
|
|
<a name="l00165"></a>00165 }
|
|
<a name="l00166"></a>00166
|
|
<a name="l00167"></a>00167 <span class="comment">// ------------------------------------------</span>
|
|
<a name="l00168"></a>00168
|
|
<a name="l00169"></a>00169 int16_t
|
|
<a name="l00170"></a><a class="code" href="class_r_c___channel.html#a5a48b57daab9a0b5feac13af9c8b768d">00170</a> <a class="code" href="class_r_c___channel.html#a5a48b57daab9a0b5feac13af9c8b768d">RC_Channel::pwm_to_angle</a>()
|
|
<a name="l00171"></a>00171 {
|
|
<a name="l00172"></a>00172 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> < <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)
|
|
<a name="l00173"></a>00173 <span class="keywordflow">return</span> _reverse * ((long)_high * (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)) / (long)(<a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>);
|
|
<a name="l00174"></a>00174 <span class="keywordflow">else</span>
|
|
<a name="l00175"></a>00175 <span class="keywordflow">return</span> _reverse * ((long)_high * (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)) / (long)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>);
|
|
<a name="l00176"></a>00176
|
|
<a name="l00177"></a>00177 <span class="comment">//return _reverse * _high * ((float)(radio_in - radio_trim) / (float)(radio_max - radio_trim));</span>
|
|
<a name="l00178"></a>00178 <span class="comment">//return _reverse * _high * ((float)(radio_in - radio_trim) / (float)(radio_trim - radio_min));</span>
|
|
<a name="l00179"></a>00179 }
|
|
<a name="l00180"></a>00180
|
|
<a name="l00181"></a>00181 <span class="keywordtype">float</span>
|
|
<a name="l00182"></a><a class="code" href="class_r_c___channel.html#a134602daa0073833f97d2934d9b97ef0">00182</a> <a class="code" href="class_r_c___channel.html#a134602daa0073833f97d2934d9b97ef0">RC_Channel::norm_input</a>()
|
|
<a name="l00183"></a>00183 {
|
|
<a name="l00184"></a>00184 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> < <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)
|
|
<a name="l00185"></a>00185 <span class="keywordflow">return</span> _reverse * (float)(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>) / (float)(<a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>);
|
|
<a name="l00186"></a>00186 <span class="keywordflow">else</span>
|
|
<a name="l00187"></a>00187 <span class="keywordflow">return</span> _reverse * (float)(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>) / (float)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>);
|
|
<a name="l00188"></a>00188 }
|
|
<a name="l00189"></a>00189
|
|
<a name="l00190"></a>00190 <span class="keywordtype">float</span>
|
|
<a name="l00191"></a><a class="code" href="class_r_c___channel.html#acbef0e8e40f867ca4d8d6c19598dcff5">00191</a> <a class="code" href="class_r_c___channel.html#acbef0e8e40f867ca4d8d6c19598dcff5">RC_Channel::norm_output</a>()
|
|
<a name="l00192"></a>00192 {
|
|
<a name="l00193"></a>00193 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a> < <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)
|
|
<a name="l00194"></a>00194 <span class="keywordflow">return</span> (<span class="keywordtype">float</span>)(<a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>) / (<span class="keywordtype">float</span>)(<a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>);
|
|
<a name="l00195"></a>00195 <span class="keywordflow">else</span>
|
|
<a name="l00196"></a>00196 <span class="keywordflow">return</span> (<span class="keywordtype">float</span>)(<a class="code" href="class_r_c___channel.html#a8238439b7d28dea76ce332d6c7a94d76">radio_out</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>) / (<span class="keywordtype">float</span>)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>);
|
|
<a name="l00197"></a>00197 }
|
|
<a name="l00198"></a>00198
|
|
<a name="l00199"></a>00199 int16_t
|
|
<a name="l00200"></a><a class="code" href="class_r_c___channel.html#abcf4a69f7323c85306e8a25b34e929b3">00200</a> <a class="code" href="class_r_c___channel.html#abcf4a69f7323c85306e8a25b34e929b3">RC_Channel::angle_to_pwm</a>()
|
|
<a name="l00201"></a>00201 {
|
|
<a name="l00202"></a>00202 <span class="keywordflow">if</span>(<a class="code" href="class_r_c___channel.html#a3dcd8fce401b9e5825d10705f1608579">servo_out</a> < 0)
|
|
<a name="l00203"></a>00203 <span class="keywordflow">return</span> ((<span class="keywordtype">long</span>)<a class="code" href="class_r_c___channel.html#a3dcd8fce401b9e5825d10705f1608579">servo_out</a> * (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a>)) / (long)_high;
|
|
<a name="l00204"></a>00204 <span class="keywordflow">else</span>
|
|
<a name="l00205"></a>00205 <span class="keywordflow">return</span> ((<span class="keywordtype">long</span>)<a class="code" href="class_r_c___channel.html#a3dcd8fce401b9e5825d10705f1608579">servo_out</a> * (long)(<a class="code" href="class_r_c___channel.html#adfe753a9a526dcc827a43f019ae66478">radio_trim</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>)) / (<span class="keywordtype">long</span>)_high;
|
|
<a name="l00206"></a>00206
|
|
<a name="l00207"></a>00207 <span class="comment">//return (((float)servo_out / (float)_high) * (float)(radio_max - radio_trim));</span>
|
|
<a name="l00208"></a>00208 <span class="comment">//return (((float)servo_out / (float)_high) * (float)(radio_trim - radio_min));</span>
|
|
<a name="l00209"></a>00209 }
|
|
<a name="l00210"></a>00210
|
|
<a name="l00211"></a>00211 <span class="comment">// ------------------------------------------</span>
|
|
<a name="l00212"></a>00212
|
|
<a name="l00213"></a>00213 int16_t
|
|
<a name="l00214"></a><a class="code" href="class_r_c___channel.html#a10f764e7d9cb160b1da9ff286b8797fb">00214</a> <a class="code" href="class_r_c___channel.html#a10f764e7d9cb160b1da9ff286b8797fb">RC_Channel::pwm_to_range</a>()
|
|
<a name="l00215"></a>00215 {
|
|
<a name="l00216"></a>00216 <span class="comment">//return (_low + ((_high - _low) * ((float)(radio_in - radio_min) / (float)(radio_max - radio_min))));</span>
|
|
<a name="l00217"></a>00217 <span class="keywordflow">return</span> (_low + ((<span class="keywordtype">long</span>)(_high - _low) * (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#af548fff701d4175c5bdf311526687c05">radio_in</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>)) / (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>));
|
|
<a name="l00218"></a>00218 }
|
|
<a name="l00219"></a>00219
|
|
<a name="l00220"></a>00220 int16_t
|
|
<a name="l00221"></a><a class="code" href="class_r_c___channel.html#ac50875b55ac524f9d0b2ee50174bd300">00221</a> <a class="code" href="class_r_c___channel.html#ac50875b55ac524f9d0b2ee50174bd300">RC_Channel::range_to_pwm</a>()
|
|
<a name="l00222"></a>00222 {
|
|
<a name="l00223"></a>00223 <span class="comment">//return (((float)(servo_out - _low) / (float)(_high - _low)) * (float)(radio_max - radio_min));</span>
|
|
<a name="l00224"></a>00224 <span class="keywordflow">return</span> ((<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#a3dcd8fce401b9e5825d10705f1608579">servo_out</a> - _low) * (<span class="keywordtype">long</span>)(<a class="code" href="class_r_c___channel.html#a5dad2c6486bbe66cee2af96f72ce4810">radio_max</a> - <a class="code" href="class_r_c___channel.html#ae635deeb549adfd63a6180ce48c8e4d5">radio_min</a>)) / (long)(_high - _low);
|
|
<a name="l00225"></a>00225 }
|
|
<a name="l00226"></a>00226
|
|
<a name="l00227"></a>00227
|
|
<a name="l00228"></a>00228
|
|
</pre></div></div>
|
|
</div>
|
|
<hr class="footer"/><address class="footer"><small>Generated on Sun Dec 26 2010 21:58:34 for ArduPilot Libraries by
|
|
<a href="http://www.doxygen.org/index.html">
|
|
<img class="footer" src="doxygen.png" alt="doxygen"/></a> 1.7.1 </small></address>
|
|
</body>
|
|
</html>
|