1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

motor test mode polished

This commit is contained in:
cTn 2013-11-12 02:24:45 +01:00
parent 7003a339ff
commit 2013095c01
3 changed files with 71 additions and 34 deletions

View file

@ -850,23 +850,33 @@ a:hover {
.tab-motor_outputs .motor_testing { .tab-motor_outputs .motor_testing {
display: none; display: none;
} }
.tab-motor_outputs .motor_testing .sliders { .tab-motor_outputs .motor_testing .sliders {
margin-top: 20px; margin-top: 20px;
}
.tab-motor_outputs .motor_testing .sliders input {
-webkit-appearance: slider-vertical;
width: 48px;
} }
.tab-motor_outputs .motor_testing .values { .tab-motor_outputs .motor_testing .sliders input {
margin-top: 5px; -webkit-appearance: slider-vertical;
}
.tab-motor_outputs .motor_testing .values li { width: 48px;
float: left; }
.tab-motor_outputs .motor_testing .values {
margin-top: 5px;
}
.tab-motor_outputs .motor_testing .values li {
float: left;
width: 51px;
text-align: center;
}
.tab-motor_outputs .motor_testing .notice {
float: right;
width: 51px; width: 490px;
text-align: center; margin-top: 20px;
padding: 5px;
border: 1px dotted silver;
} }
.tab-sensors { .tab-sensors {
} }

View file

@ -49,27 +49,38 @@
Bars on the <strong>right</strong> are representing raw PWM signal for <strong>Servos</strong>.<br /> Bars on the <strong>right</strong> are representing raw PWM signal for <strong>Servos</strong>.<br />
</p> </p>
<div class="motor_testing"> <div class="motor_testing">
<div class="sliders"> <div class="left">
<input type="range" min="1000" max="2000" value="1000" /> <div class="sliders">
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" /> <input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
<input type="range" min="1000" max="2000" value="1000" disabled="disabled" />
</div>
<div class="values">
<ul>
<li>1000</li>
<li>1000</li>
<li>1000</li>
<li>1000</li>
<li>1000</li>
<li>1000</li>
<li>1000</li>
<li>1000</li>
</ul>
</div>
</div> </div>
<div class="values"> <div class="notice">
<ul> <strong>Motor Test Mode Notice:</strong><br />
<li>1000</li> Moving the sliders to the top will cause the motors to <strong>spin up</strong>.<br />
<li>1000</li> In order to prevent injury you must <strong style="color: red">remove ALL propellers</strong> before using this feature.<br />
<li>1000</li> If you understand these instructions check the <strong>box</strong> below to <strong style="color: green">enable</strong> motor test mode.<br />
<li>1000</li> <br />
<li>1000</li> <input type="checkbox" />
<li>1000</li>
<li>1000</li>
<li>1000</li>
</ul>
</div> </div>
<div class="cler-both"></div>
</div> </div>
</div> </div>

View file

@ -24,6 +24,22 @@ function tab_initialize_motor_outputs() {
send_message(MSP_codes.MSP_SET_MOTOR, buffer_out); send_message(MSP_codes.MSP_SET_MOTOR, buffer_out);
}); });
$('div.notice input').change(function() {
if ($(this).is(':checked')) {
$('div.sliders input').prop('disabled', false);
} else {
// disable sliders
$('div.sliders input').prop('disabled', true);
// change all values to default
$('div.sliders input').val(1000);
$('div.values li').html(1000);
// trigger change event so values are sent to mcu
$('div.sliders input').change();
}
});
// enable Motor data pulling // enable Motor data pulling
timers.push(setInterval(motorPoll, 50)); timers.push(setInterval(motorPoll, 50));
} }