mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-24 16:55:24 +03:00
Merge branch 'development'
This commit is contained in:
commit
716457b0ed
51 changed files with 2251 additions and 1492 deletions
|
@ -30,12 +30,21 @@ function configuration_backup(callback) {
|
|||
MSP_codes.MSP_PID,
|
||||
MSP_codes.MSP_RC_TUNING,
|
||||
MSP_codes.MSP_ACC_TRIM,
|
||||
MSP_codes.MSP_SERVO_CONF,
|
||||
MSP_codes.MSP_CHANNEL_FORWARDING,
|
||||
MSP_codes.MSP_SERVO_CONFIGURATIONS,
|
||||
MSP_codes.MSP_MODE_RANGES,
|
||||
MSP_codes.MSP_ADJUSTMENT_RANGES
|
||||
];
|
||||
|
||||
function update_profile_specific_data_list() {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
profileSpecificData.push(MSP_codes.MSP_CHANNEL_FORWARDING);
|
||||
} else {
|
||||
profileSpecificData.push(MSP_codes.MSP_SERVO_MIX_RULES);
|
||||
}
|
||||
}
|
||||
|
||||
update_profile_specific_data_list();
|
||||
|
||||
function fetch_specific_data() {
|
||||
var fetchingProfile = 0,
|
||||
codeKey = 0;
|
||||
|
@ -54,6 +63,7 @@ function configuration_backup(callback) {
|
|||
'RC': jQuery.extend(true, {}, RC_tuning),
|
||||
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], ADJUSTMENT_RANGES)
|
||||
});
|
||||
|
@ -428,6 +438,38 @@ function configuration_restore(callback) {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.lt(migratedVersion, '0.66.0')) {
|
||||
// api 1.12 updated servo configuration protocol and added servo mixer rules
|
||||
for (var profileIndex = 0; i < configuration.profiles.length; i++) {
|
||||
|
||||
if (semver.eq(configuration.apiVersion, '1.10.0')) {
|
||||
// drop two unused servo configurations
|
||||
while (configuration.profiles[profileIndex].ServoConfig.length > 8) {
|
||||
configuration.profiles[profileIndex].ServoConfig.pop();
|
||||
}
|
||||
}
|
||||
|
||||
for (var i = 0; i < configuration.profiles[profileIndex].ServoConfig.length; i++) {
|
||||
var servoConfig = profiles[profileIndex].ServoConfig;
|
||||
|
||||
servoConfig[i].angleAtMin = 90;
|
||||
servoConfig[i].angleAtMax = 90;
|
||||
servoConfig[i].reversedInputSources = 0;
|
||||
|
||||
// set the rate to 0 if an invalid value is detected.
|
||||
if (servoConfig[i].rate < -100 || servoConfig[i].rate > 100) {
|
||||
servoConfig[i].rate = 0;
|
||||
}
|
||||
}
|
||||
|
||||
configuration.profiles[profileIndex].ServoRules = [];
|
||||
}
|
||||
|
||||
migratedVersion = '0.66.0';
|
||||
|
||||
appliedMigrationsCount++;
|
||||
}
|
||||
|
||||
if (appliedMigrationsCount > 0) {
|
||||
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
|
||||
}
|
||||
|
@ -444,9 +486,7 @@ function configuration_restore(callback) {
|
|||
MSP_codes.MSP_SET_PID_CONTROLLER,
|
||||
MSP_codes.MSP_SET_PID,
|
||||
MSP_codes.MSP_SET_RC_TUNING,
|
||||
MSP_codes.MSP_SET_ACC_TRIM,
|
||||
MSP_codes.MSP_SET_SERVO_CONF,
|
||||
MSP_codes.MSP_SET_CHANNEL_FORWARDING
|
||||
MSP_codes.MSP_SET_ACC_TRIM
|
||||
];
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () {
|
||||
|
@ -472,6 +512,7 @@ function configuration_restore(callback) {
|
|||
RC_tuning = configuration.profiles[profile].RC;
|
||||
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
}
|
||||
|
@ -501,6 +542,14 @@ function configuration_restore(callback) {
|
|||
});
|
||||
}
|
||||
|
||||
function upload_servo_mix_rules() {
|
||||
MSP.sendServoMixRules(upload_servo_configuration);
|
||||
}
|
||||
|
||||
function upload_servo_configuration() {
|
||||
MSP.sendServoConfigurations(upload_mode_ranges);
|
||||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
MSP.sendModeRanges(upload_adjustment_ranges);
|
||||
}
|
||||
|
@ -510,7 +559,7 @@ function configuration_restore(callback) {
|
|||
}
|
||||
// start uploading
|
||||
load_objects(0);
|
||||
upload_mode_ranges();
|
||||
upload_servo_configuration();
|
||||
}
|
||||
|
||||
function upload_unique_data() {
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
'use strict';
|
||||
|
||||
var CONFIGURATOR = {
|
||||
'releaseDate': 1432389468227, // new Date().getTime() - Sat May 23 2015 14:57:54 GMT+0100 (BST)
|
||||
'releaseDate': 1446278768375, // new Date().getTime() - Fri Oct 02 2015 20:50:49 GMT+0100 (GMT Daylight Time)
|
||||
|
||||
// all versions are specified and compared using semantic versioning http://semver.org/
|
||||
'apiVersionAccepted': '1.2.0',
|
||||
|
@ -86,6 +86,7 @@ var MODE_RANGES = [];
|
|||
var ADJUSTMENT_RANGES = [];
|
||||
|
||||
var SERVO_CONFIG = [];
|
||||
var SERVO_RULES = [];
|
||||
|
||||
var SERIAL_CONFIG = {
|
||||
ports: [],
|
||||
|
|
6
js/libraries/d3.min.js
vendored
6
js/libraries/d3.min.js
vendored
File diff suppressed because one or more lines are too long
4
js/libraries/jquery-2.1.3.min.js
vendored
4
js/libraries/jquery-2.1.3.min.js
vendored
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
4
js/libraries/jquery-2.1.4.min.js
vendored
Normal file
4
js/libraries/jquery-2.1.4.min.js
vendored
Normal file
File diff suppressed because one or more lines are too long
1
js/libraries/jquery-2.1.4.min.map
Normal file
1
js/libraries/jquery-2.1.4.min.map
Normal file
File diff suppressed because one or more lines are too long
13
js/libraries/jquery-ui-1.11.4.min.js
vendored
Normal file
13
js/libraries/jquery-ui-1.11.4.min.js
vendored
Normal file
File diff suppressed because one or more lines are too long
|
@ -16,13 +16,13 @@ THREE.SpriteCanvasMaterial = function ( parameters ) {
|
|||
};
|
||||
|
||||
THREE.SpriteCanvasMaterial.prototype = Object.create( THREE.Material.prototype );
|
||||
THREE.SpriteCanvasMaterial.prototype.constructor = THREE.SpriteCanvasMaterial;
|
||||
|
||||
THREE.SpriteCanvasMaterial.prototype.clone = function () {
|
||||
|
||||
var material = new THREE.SpriteCanvasMaterial();
|
||||
|
||||
THREE.Material.prototype.clone.call( this, material );
|
||||
|
||||
material.copy( this );
|
||||
material.color.copy( this.color );
|
||||
material.program = this.program;
|
||||
|
||||
|
@ -58,12 +58,14 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
_viewportWidth = _canvasWidth,
|
||||
_viewportHeight = _canvasHeight,
|
||||
|
||||
pixelRatio = 1,
|
||||
|
||||
_context = _canvas.getContext( '2d', {
|
||||
alpha: parameters.alpha === true
|
||||
} ),
|
||||
|
||||
_clearColor = new THREE.Color( 0x000000 ),
|
||||
_clearAlpha = 0,
|
||||
_clearAlpha = parameters.alpha === true ? 0 : 1,
|
||||
|
||||
_contextGlobalAlpha = 1,
|
||||
_contextGlobalCompositeOperation = 0,
|
||||
|
@ -122,12 +124,6 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
this.domElement = _canvas;
|
||||
|
||||
this.devicePixelRatio = parameters.devicePixelRatio !== undefined
|
||||
? parameters.devicePixelRatio
|
||||
: self.devicePixelRatio !== undefined
|
||||
? self.devicePixelRatio
|
||||
: 1;
|
||||
|
||||
this.autoClear = true;
|
||||
this.sortObjects = true;
|
||||
this.sortElements = true;
|
||||
|
@ -141,17 +137,43 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
|
||||
// WebGLRenderer compatibility
|
||||
|
||||
this.supportsVertexTextures = function () {};
|
||||
this.setFaceCulling = function () {};
|
||||
|
||||
// API
|
||||
|
||||
this.getContext = function () {
|
||||
|
||||
return _context;
|
||||
|
||||
};
|
||||
|
||||
this.getContextAttributes = function () {
|
||||
|
||||
return _context.getContextAttributes();
|
||||
|
||||
};
|
||||
|
||||
this.getPixelRatio = function () {
|
||||
|
||||
return pixelRatio;
|
||||
|
||||
};
|
||||
|
||||
this.setPixelRatio = function ( value ) {
|
||||
|
||||
if ( value !== undefined ) pixelRatio = value;
|
||||
|
||||
};
|
||||
|
||||
this.setSize = function ( width, height, updateStyle ) {
|
||||
|
||||
_canvasWidth = width * this.devicePixelRatio;
|
||||
_canvasHeight = height * this.devicePixelRatio;
|
||||
_canvasWidth = width * pixelRatio;
|
||||
_canvasHeight = height * pixelRatio;
|
||||
|
||||
_canvas.width = _canvasWidth;
|
||||
_canvas.height = _canvasHeight;
|
||||
|
@ -166,7 +188,7 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
}
|
||||
|
||||
_clipBox.min.set( -_canvasWidthHalf, -_canvasHeightHalf ),
|
||||
_clipBox.min.set( - _canvasWidthHalf, - _canvasHeightHalf );
|
||||
_clipBox.max.set( _canvasWidthHalf, _canvasHeightHalf );
|
||||
|
||||
_clearBox.min.set( - _canvasWidthHalf, - _canvasHeightHalf );
|
||||
|
@ -186,11 +208,11 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
this.setViewport = function ( x, y, width, height ) {
|
||||
|
||||
_viewportX = x * this.devicePixelRatio;
|
||||
_viewportY = y * this.devicePixelRatio;
|
||||
_viewportX = x * pixelRatio;
|
||||
_viewportY = y * pixelRatio;
|
||||
|
||||
_viewportWidth = width * this.devicePixelRatio;
|
||||
_viewportHeight = height * this.devicePixelRatio;
|
||||
_viewportWidth = width * pixelRatio;
|
||||
_viewportHeight = height * pixelRatio;
|
||||
|
||||
};
|
||||
|
||||
|
@ -240,17 +262,17 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
_clearBox.expandByScalar( 2 );
|
||||
|
||||
_clearBox.min.x = _clearBox.min.x + _canvasWidthHalf;
|
||||
_clearBox.min.y = - _clearBox.min.y + _canvasHeightHalf;
|
||||
_clearBox.min.y = - _clearBox.min.y + _canvasHeightHalf; // higher y value !
|
||||
_clearBox.max.x = _clearBox.max.x + _canvasWidthHalf;
|
||||
_clearBox.max.y = - _clearBox.max.y + _canvasHeightHalf;
|
||||
_clearBox.max.y = - _clearBox.max.y + _canvasHeightHalf; // lower y value !
|
||||
|
||||
if ( _clearAlpha < 1 ) {
|
||||
|
||||
_context.clearRect(
|
||||
_clearBox.min.x | 0,
|
||||
_clearBox.min.y | 0,
|
||||
_clearBox.max.y | 0,
|
||||
( _clearBox.max.x - _clearBox.min.x ) | 0,
|
||||
( _clearBox.max.y - _clearBox.min.y ) | 0
|
||||
( _clearBox.min.y - _clearBox.max.y ) | 0
|
||||
);
|
||||
|
||||
}
|
||||
|
@ -264,9 +286,9 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
_context.fillRect(
|
||||
_clearBox.min.x | 0,
|
||||
_clearBox.min.y | 0,
|
||||
_clearBox.max.y | 0,
|
||||
( _clearBox.max.x - _clearBox.min.x ) | 0,
|
||||
( _clearBox.max.y - _clearBox.min.y ) | 0
|
||||
( _clearBox.min.y - _clearBox.max.y ) | 0
|
||||
);
|
||||
|
||||
}
|
||||
|
@ -496,53 +518,42 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
var texture = material.map;
|
||||
|
||||
if ( texture !== null && texture.image !== undefined ) {
|
||||
|
||||
if ( texture.hasEventListener( 'update', onTextureUpdate ) === false ) {
|
||||
|
||||
if ( texture.image.width > 0 ) {
|
||||
|
||||
textureToPattern( texture );
|
||||
|
||||
}
|
||||
|
||||
texture.addEventListener( 'update', onTextureUpdate );
|
||||
|
||||
}
|
||||
if ( texture !== null ) {
|
||||
|
||||
var pattern = _patterns[ texture.id ];
|
||||
|
||||
if ( pattern !== undefined ) {
|
||||
if ( pattern === undefined || pattern.version !== texture.version ) {
|
||||
|
||||
setFillStyle( pattern );
|
||||
|
||||
} else {
|
||||
|
||||
setFillStyle( 'rgba( 0, 0, 0, 1 )' );
|
||||
pattern = textureToPattern( texture );
|
||||
_patterns[ texture.id ] = pattern;
|
||||
|
||||
}
|
||||
|
||||
//
|
||||
if ( pattern.canvas !== undefined ) {
|
||||
|
||||
var bitmap = texture.image;
|
||||
setFillStyle( pattern.canvas );
|
||||
|
||||
var ox = bitmap.width * texture.offset.x;
|
||||
var oy = bitmap.height * texture.offset.y;
|
||||
var bitmap = texture.image;
|
||||
|
||||
var sx = bitmap.width * texture.repeat.x;
|
||||
var sy = bitmap.height * texture.repeat.y;
|
||||
var ox = bitmap.width * texture.offset.x;
|
||||
var oy = bitmap.height * texture.offset.y;
|
||||
|
||||
var cx = scaleX / sx;
|
||||
var cy = scaleY / sy;
|
||||
var sx = bitmap.width * texture.repeat.x;
|
||||
var sy = bitmap.height * texture.repeat.y;
|
||||
|
||||
_context.save();
|
||||
_context.translate( v1.x, v1.y );
|
||||
if ( material.rotation !== 0 ) _context.rotate( material.rotation );
|
||||
_context.translate( - scaleX / 2, - scaleY / 2 );
|
||||
_context.scale( cx, cy );
|
||||
_context.translate( - ox, - oy );
|
||||
_context.fillRect( ox, oy, sx, sy );
|
||||
_context.restore();
|
||||
var cx = scaleX / sx;
|
||||
var cy = scaleY / sy;
|
||||
|
||||
_context.save();
|
||||
_context.translate( v1.x, v1.y );
|
||||
if ( material.rotation !== 0 ) _context.rotate( material.rotation );
|
||||
_context.translate( - scaleX / 2, - scaleY / 2 );
|
||||
_context.scale( cx, cy );
|
||||
_context.translate( - ox, - oy );
|
||||
_context.fillRect( ox, oy, sx, sy );
|
||||
_context.restore();
|
||||
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
|
@ -704,7 +715,9 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
if ( material.map !== null ) {
|
||||
|
||||
if ( material.map.mapping instanceof THREE.UVMapping ) {
|
||||
var mapping = material.map.mapping;
|
||||
|
||||
if ( mapping === THREE.UVMapping ) {
|
||||
|
||||
_uvs = element.uvs;
|
||||
patternPath( _v1x, _v1y, _v2x, _v2y, _v3x, _v3y, _uvs[ uv1 ].x, _uvs[ uv1 ].y, _uvs[ uv2 ].x, _uvs[ uv2 ].y, _uvs[ uv3 ].x, _uvs[ uv3 ].y, material.map );
|
||||
|
@ -713,7 +726,7 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
} else if ( material.envMap !== null ) {
|
||||
|
||||
if ( material.envMap.mapping instanceof THREE.SphericalReflectionMapping ) {
|
||||
if ( material.envMap.mapping === THREE.SphericalReflectionMapping ) {
|
||||
|
||||
_normal.copy( element.vertexNormalsModel[ uv1 ] ).applyMatrix3( _normalViewMatrix );
|
||||
_uv1x = 0.5 * _normal.x + 0.5;
|
||||
|
@ -729,25 +742,8 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
patternPath( _v1x, _v1y, _v2x, _v2y, _v3x, _v3y, _uv1x, _uv1y, _uv2x, _uv2y, _uv3x, _uv3y, material.envMap );
|
||||
|
||||
} else if ( material.envMap.mapping instanceof THREE.SphericalRefractionMapping ) {
|
||||
|
||||
_normal.copy( element.vertexNormalsModel[ uv1 ] ).applyMatrix3( _normalViewMatrix );
|
||||
_uv1x = - 0.5 * _normal.x + 0.5;
|
||||
_uv1y = - 0.5 * _normal.y + 0.5;
|
||||
|
||||
_normal.copy( element.vertexNormalsModel[ uv2 ] ).applyMatrix3( _normalViewMatrix );
|
||||
_uv2x = - 0.5 * _normal.x + 0.5;
|
||||
_uv2y = - 0.5 * _normal.y + 0.5;
|
||||
|
||||
_normal.copy( element.vertexNormalsModel[ uv3 ] ).applyMatrix3( _normalViewMatrix );
|
||||
_uv3x = - 0.5 * _normal.x + 0.5;
|
||||
_uv3y = - 0.5 * _normal.y + 0.5;
|
||||
|
||||
patternPath( _v1x, _v1y, _v2x, _v2y, _v3x, _v3y, _uv1x, _uv1y, _uv2x, _uv2y, _uv3x, _uv3y, material.envMap );
|
||||
|
||||
}
|
||||
|
||||
|
||||
} else {
|
||||
|
||||
_color.copy( material.color );
|
||||
|
@ -826,18 +822,18 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
|
||||
}
|
||||
|
||||
function onTextureUpdate ( event ) {
|
||||
|
||||
textureToPattern( event.target );
|
||||
|
||||
}
|
||||
|
||||
function textureToPattern( texture ) {
|
||||
|
||||
if ( texture instanceof THREE.CompressedTexture ) return;
|
||||
if ( texture.version === 0 ||
|
||||
texture instanceof THREE.CompressedTexture ||
|
||||
texture instanceof THREE.DataTexture ) {
|
||||
|
||||
var repeatX = texture.wrapS === THREE.RepeatWrapping;
|
||||
var repeatY = texture.wrapT === THREE.RepeatWrapping;
|
||||
return {
|
||||
canvas: undefined,
|
||||
version: texture.version
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
var image = texture.image;
|
||||
|
||||
|
@ -849,45 +845,51 @@ THREE.CanvasRenderer = function ( parameters ) {
|
|||
context.setTransform( 1, 0, 0, - 1, 0, image.height );
|
||||
context.drawImage( image, 0, 0 );
|
||||
|
||||
_patterns[ texture.id ] = _context.createPattern(
|
||||
canvas, repeatX === true && repeatY === true
|
||||
? 'repeat'
|
||||
: repeatX === true && repeatY === false
|
||||
? 'repeat-x'
|
||||
: repeatX === false && repeatY === true
|
||||
? 'repeat-y'
|
||||
: 'no-repeat'
|
||||
);
|
||||
var repeatX = texture.wrapS === THREE.RepeatWrapping;
|
||||
var repeatY = texture.wrapT === THREE.RepeatWrapping;
|
||||
|
||||
var repeat = 'no-repeat';
|
||||
|
||||
if ( repeatX === true && repeatY === true ) {
|
||||
|
||||
repeat = 'repeat';
|
||||
|
||||
} else if ( repeatX === true ) {
|
||||
|
||||
repeat = 'repeat-x';
|
||||
|
||||
} else if ( repeatY === true ) {
|
||||
|
||||
repeat = 'repeat-y';
|
||||
|
||||
}
|
||||
|
||||
return {
|
||||
canvas: _context.createPattern( canvas, repeat ),
|
||||
version: texture.version
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
function patternPath( x0, y0, x1, y1, x2, y2, u0, v0, u1, v1, u2, v2, texture ) {
|
||||
|
||||
if ( texture instanceof THREE.DataTexture ) return;
|
||||
var pattern = _patterns[ texture.id ];
|
||||
|
||||
if ( texture.hasEventListener( 'update', onTextureUpdate ) === false ) {
|
||||
if ( pattern === undefined || pattern.version !== texture.version ) {
|
||||
|
||||
if ( texture.image !== undefined && texture.image.width > 0 ) {
|
||||
|
||||
textureToPattern( texture );
|
||||
|
||||
}
|
||||
|
||||
texture.addEventListener( 'update', onTextureUpdate );
|
||||
pattern = textureToPattern( texture );
|
||||
_patterns[ texture.id ] = pattern;
|
||||
|
||||
}
|
||||
|
||||
var pattern = _patterns[ texture.id ];
|
||||
if ( pattern.canvas !== undefined ) {
|
||||
|
||||
if ( pattern !== undefined ) {
|
||||
|
||||
setFillStyle( pattern );
|
||||
setFillStyle( pattern.canvas );
|
||||
|
||||
} else {
|
||||
|
||||
setFillStyle( 'rgba(0,0,0,1)' );
|
||||
setFillStyle( 'rgba( 0, 0, 0, 1)' );
|
||||
_context.fill();
|
||||
|
||||
return;
|
||||
|
||||
}
|
||||
|
|
|
@ -10,6 +10,7 @@ THREE.RenderableObject = function () {
|
|||
|
||||
this.object = null;
|
||||
this.z = 0;
|
||||
this.renderOrder = 0;
|
||||
|
||||
};
|
||||
|
||||
|
@ -33,6 +34,7 @@ THREE.RenderableFace = function () {
|
|||
this.uvs = [ new THREE.Vector2(), new THREE.Vector2(), new THREE.Vector2() ];
|
||||
|
||||
this.z = 0;
|
||||
this.renderOrder = 0;
|
||||
|
||||
};
|
||||
|
||||
|
@ -68,6 +70,7 @@ THREE.RenderableLine = function () {
|
|||
this.material = null;
|
||||
|
||||
this.z = 0;
|
||||
this.renderOrder = 0;
|
||||
|
||||
};
|
||||
|
||||
|
@ -87,6 +90,7 @@ THREE.RenderableSprite = function () {
|
|||
this.scale = new THREE.Vector2();
|
||||
|
||||
this.material = null;
|
||||
this.renderOrder = 0;
|
||||
|
||||
};
|
||||
|
||||
|
@ -102,10 +106,6 @@ THREE.Projector = function () {
|
|||
|
||||
_renderData = { objects: [], lights: [], elements: [] },
|
||||
|
||||
_vA = new THREE.Vector3(),
|
||||
_vB = new THREE.Vector3(),
|
||||
_vC = new THREE.Vector3(),
|
||||
|
||||
_vector3 = new THREE.Vector3(),
|
||||
_vector4 = new THREE.Vector4(),
|
||||
|
||||
|
@ -126,7 +126,7 @@ THREE.Projector = function () {
|
|||
|
||||
_clippedVertex1PositionScreen = new THREE.Vector4(),
|
||||
_clippedVertex2PositionScreen = new THREE.Vector4();
|
||||
|
||||
|
||||
//
|
||||
|
||||
this.projectVector = function ( vector, camera ) {
|
||||
|
@ -145,10 +145,10 @@ THREE.Projector = function () {
|
|||
|
||||
this.pickingRay = function ( vector, camera ) {
|
||||
|
||||
console.error( 'THREE.Projector: .pickingRay() has been removed.' );
|
||||
console.error( 'THREE.Projector: .pickingRay() is now raycaster.setFromCamera().' );
|
||||
|
||||
};
|
||||
|
||||
|
||||
//
|
||||
|
||||
var RenderList = function () {
|
||||
|
@ -247,6 +247,7 @@ THREE.Projector = function () {
|
|||
_line.v1.copy( v1 );
|
||||
_line.v2.copy( v2 );
|
||||
_line.z = ( v1.positionScreen.z + v2.positionScreen.z ) / 2;
|
||||
_line.renderOrder = object.renderOrder;
|
||||
|
||||
_line.material = object.material;
|
||||
|
||||
|
@ -271,19 +272,21 @@ THREE.Projector = function () {
|
|||
_face.v2.copy( v2 );
|
||||
_face.v3.copy( v3 );
|
||||
_face.z = ( v1.positionScreen.z + v2.positionScreen.z + v3.positionScreen.z ) / 3;
|
||||
_face.renderOrder = object.renderOrder;
|
||||
|
||||
// use first vertex normal as face normal
|
||||
|
||||
_face.normalModel.fromArray( normals, a * 3 );
|
||||
_face.normalModel.applyMatrix3( normalMatrix ).normalize();
|
||||
|
||||
for ( var i = 0; i < 3; i ++ ) {
|
||||
|
||||
var offset = arguments[ i ] * 3;
|
||||
var normal = _face.vertexNormalsModel[ i ];
|
||||
|
||||
normal.set( normals[ offset ], normals[ offset + 1 ], normals[ offset + 2 ] );
|
||||
normal.fromArray( normals, arguments[ i ] * 3 );
|
||||
normal.applyMatrix3( normalMatrix ).normalize();
|
||||
|
||||
var offset2 = arguments[ i ] * 2;
|
||||
|
||||
var uv = _face.uvs[ i ];
|
||||
uv.set( uvs[ offset2 ], uvs[ offset2 + 1 ] );
|
||||
uv.fromArray( uvs, arguments[ i ] * 2 );
|
||||
|
||||
}
|
||||
|
||||
|
@ -322,7 +325,7 @@ THREE.Projector = function () {
|
|||
_renderData.elements.length = 0;
|
||||
|
||||
if ( scene.autoUpdate === true ) scene.updateMatrixWorld();
|
||||
if ( camera.parent === undefined ) camera.updateMatrixWorld();
|
||||
if ( camera.parent === null ) camera.updateMatrixWorld();
|
||||
|
||||
_viewMatrix.copy( camera.matrixWorldInverse.getInverse( camera.matrixWorld ) );
|
||||
_viewProjectionMatrix.multiplyMatrices( camera.projectionMatrix, _viewMatrix );
|
||||
|
@ -344,7 +347,9 @@ THREE.Projector = function () {
|
|||
|
||||
} else if ( object instanceof THREE.Mesh || object instanceof THREE.Line || object instanceof THREE.Sprite ) {
|
||||
|
||||
if ( object.material.visible === false ) return;
|
||||
var material = object.material;
|
||||
|
||||
if ( material.visible === false ) return;
|
||||
|
||||
if ( object.frustumCulled === false || _frustum.intersectsObject( object ) === true ) {
|
||||
|
||||
|
@ -352,17 +357,10 @@ THREE.Projector = function () {
|
|||
_object.id = object.id;
|
||||
_object.object = object;
|
||||
|
||||
if ( object.renderDepth !== null ) {
|
||||
|
||||
_object.z = object.renderDepth;
|
||||
|
||||
} else {
|
||||
|
||||
_vector3.setFromMatrixPosition( object.matrixWorld );
|
||||
_vector3.applyProjection( _viewProjectionMatrix );
|
||||
_object.z = _vector3.z;
|
||||
|
||||
}
|
||||
_vector3.setFromMatrixPosition( object.matrixWorld );
|
||||
_vector3.applyProjection( _viewProjectionMatrix );
|
||||
_object.z = _vector3.z;
|
||||
_object.renderOrder = object.renderOrder;
|
||||
|
||||
_renderData.objects.push( _object );
|
||||
|
||||
|
@ -396,7 +394,7 @@ THREE.Projector = function () {
|
|||
if ( geometry instanceof THREE.BufferGeometry ) {
|
||||
|
||||
var attributes = geometry.attributes;
|
||||
var offsets = geometry.offsets;
|
||||
var groups = geometry.groups;
|
||||
|
||||
if ( attributes.position === undefined ) continue;
|
||||
|
||||
|
@ -432,20 +430,19 @@ THREE.Projector = function () {
|
|||
|
||||
}
|
||||
|
||||
if ( attributes.index !== undefined ) {
|
||||
if ( geometry.index !== null ) {
|
||||
|
||||
var indices = attributes.index.array;
|
||||
var indices = geometry.index.array;
|
||||
|
||||
if ( offsets.length > 0 ) {
|
||||
if ( groups.length > 0 ) {
|
||||
|
||||
for ( var o = 0; o < offsets.length; o ++ ) {
|
||||
for ( var o = 0; o < groups.length; o ++ ) {
|
||||
|
||||
var offset = offsets[ o ];
|
||||
var index = offset.index;
|
||||
var group = groups[ o ];
|
||||
|
||||
for ( var i = offset.start, l = offset.start + offset.count; i < l; i += 3 ) {
|
||||
for ( var i = group.start, l = group.start + group.count; i < l; i += 3 ) {
|
||||
|
||||
renderList.pushTriangle( indices[ i ] + index, indices[ i + 1 ] + index, indices[ i + 2 ] + index );
|
||||
renderList.pushTriangle( indices[ i ], indices[ i + 1 ], indices[ i + 2 ] );
|
||||
|
||||
}
|
||||
|
||||
|
@ -479,13 +476,40 @@ THREE.Projector = function () {
|
|||
|
||||
_normalMatrix.getNormalMatrix( _modelMatrix );
|
||||
|
||||
var isFaceMaterial = object.material instanceof THREE.MeshFaceMaterial;
|
||||
var material = object.material;
|
||||
|
||||
var isFaceMaterial = material instanceof THREE.MeshFaceMaterial;
|
||||
var objectMaterials = isFaceMaterial === true ? object.material : null;
|
||||
|
||||
for ( var v = 0, vl = vertices.length; v < vl; v ++ ) {
|
||||
|
||||
var vertex = vertices[ v ];
|
||||
renderList.pushVertex( vertex.x, vertex.y, vertex.z );
|
||||
|
||||
_vector3.copy( vertex );
|
||||
|
||||
if ( material.morphTargets === true ) {
|
||||
|
||||
var morphTargets = geometry.morphTargets;
|
||||
var morphInfluences = object.morphTargetInfluences;
|
||||
|
||||
for ( var t = 0, tl = morphTargets.length; t < tl; t ++ ) {
|
||||
|
||||
var influence = morphInfluences[ t ];
|
||||
|
||||
if ( influence === 0 ) continue;
|
||||
|
||||
var target = morphTargets[ t ];
|
||||
var targetVertex = target.vertices[ v ];
|
||||
|
||||
_vector3.x += ( targetVertex.x - vertex.x ) * influence;
|
||||
_vector3.y += ( targetVertex.y - vertex.y ) * influence;
|
||||
_vector3.z += ( targetVertex.z - vertex.z ) * influence;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
renderList.pushVertex( _vector3.x, _vector3.y, _vector3.z );
|
||||
|
||||
}
|
||||
|
||||
|
@ -493,7 +517,7 @@ THREE.Projector = function () {
|
|||
|
||||
var face = faces[ f ];
|
||||
|
||||
var material = isFaceMaterial === true
|
||||
material = isFaceMaterial === true
|
||||
? objectMaterials.materials[ face.materialIndex ]
|
||||
: object.material;
|
||||
|
||||
|
@ -505,58 +529,15 @@ THREE.Projector = function () {
|
|||
var v2 = _vertexPool[ face.b ];
|
||||
var v3 = _vertexPool[ face.c ];
|
||||
|
||||
if ( material.morphTargets === true ) {
|
||||
|
||||
var morphTargets = geometry.morphTargets;
|
||||
var morphInfluences = object.morphTargetInfluences;
|
||||
|
||||
var v1p = v1.position;
|
||||
var v2p = v2.position;
|
||||
var v3p = v3.position;
|
||||
|
||||
_vA.set( 0, 0, 0 );
|
||||
_vB.set( 0, 0, 0 );
|
||||
_vC.set( 0, 0, 0 );
|
||||
|
||||
for ( var t = 0, tl = morphTargets.length; t < tl; t ++ ) {
|
||||
|
||||
var influence = morphInfluences[ t ];
|
||||
|
||||
if ( influence === 0 ) continue;
|
||||
|
||||
var targets = morphTargets[ t ].vertices;
|
||||
|
||||
_vA.x += ( targets[ face.a ].x - v1p.x ) * influence;
|
||||
_vA.y += ( targets[ face.a ].y - v1p.y ) * influence;
|
||||
_vA.z += ( targets[ face.a ].z - v1p.z ) * influence;
|
||||
|
||||
_vB.x += ( targets[ face.b ].x - v2p.x ) * influence;
|
||||
_vB.y += ( targets[ face.b ].y - v2p.y ) * influence;
|
||||
_vB.z += ( targets[ face.b ].z - v2p.z ) * influence;
|
||||
|
||||
_vC.x += ( targets[ face.c ].x - v3p.x ) * influence;
|
||||
_vC.y += ( targets[ face.c ].y - v3p.y ) * influence;
|
||||
_vC.z += ( targets[ face.c ].z - v3p.z ) * influence;
|
||||
|
||||
}
|
||||
|
||||
v1.position.add( _vA );
|
||||
v2.position.add( _vB );
|
||||
v3.position.add( _vC );
|
||||
|
||||
renderList.projectVertex( v1 );
|
||||
renderList.projectVertex( v2 );
|
||||
renderList.projectVertex( v3 );
|
||||
|
||||
}
|
||||
|
||||
if ( renderList.checkTriangleVisibility( v1, v2, v3 ) === false ) continue;
|
||||
|
||||
var visible = renderList.checkBackfaceCulling( v1, v2, v3 );
|
||||
|
||||
if ( side !== THREE.DoubleSide ) {
|
||||
|
||||
if ( side === THREE.FrontSide && visible === false ) continue;
|
||||
if ( side === THREE.BackSide && visible === true ) continue;
|
||||
|
||||
}
|
||||
|
||||
_face = getNextFaceInPool();
|
||||
|
@ -611,6 +592,7 @@ THREE.Projector = function () {
|
|||
_face.material = material;
|
||||
|
||||
_face.z = ( v1.positionScreen.z + v2.positionScreen.z + v3.positionScreen.z ) / 3;
|
||||
_face.renderOrder = object.renderOrder;
|
||||
|
||||
_renderData.elements.push( _face );
|
||||
|
||||
|
@ -634,9 +616,9 @@ THREE.Projector = function () {
|
|||
|
||||
}
|
||||
|
||||
if ( attributes.index !== undefined ) {
|
||||
if ( geometry.index !== null ) {
|
||||
|
||||
var indices = attributes.index.array;
|
||||
var indices = geometry.index.array;
|
||||
|
||||
for ( var i = 0, l = indices.length; i < l; i += 2 ) {
|
||||
|
||||
|
@ -646,7 +628,7 @@ THREE.Projector = function () {
|
|||
|
||||
} else {
|
||||
|
||||
var step = object.mode === THREE.LinePieces ? 2 : 1;
|
||||
var step = object instanceof THREE.LineSegments ? 2 : 1;
|
||||
|
||||
for ( var i = 0, l = ( positions.length / 3 ) - 1; i < l; i += step ) {
|
||||
|
||||
|
@ -669,8 +651,7 @@ THREE.Projector = function () {
|
|||
v1 = getNextVertexInPool();
|
||||
v1.positionScreen.copy( vertices[ 0 ] ).applyMatrix4( _modelViewProjectionMatrix );
|
||||
|
||||
// Handle LineStrip and LinePieces
|
||||
var step = object.mode === THREE.LinePieces ? 2 : 1;
|
||||
var step = object instanceof THREE.LineSegments ? 2 : 1;
|
||||
|
||||
for ( var v = 1, vl = vertices.length; v < vl; v ++ ) {
|
||||
|
||||
|
@ -697,6 +678,7 @@ THREE.Projector = function () {
|
|||
_line.v2.positionScreen.copy( _clippedVertex2PositionScreen );
|
||||
|
||||
_line.z = Math.max( _clippedVertex1PositionScreen.z, _clippedVertex2PositionScreen.z );
|
||||
_line.renderOrder = object.renderOrder;
|
||||
|
||||
_line.material = object.material;
|
||||
|
||||
|
@ -731,6 +713,7 @@ THREE.Projector = function () {
|
|||
_sprite.x = _vector4.x * invW;
|
||||
_sprite.y = _vector4.y * invW;
|
||||
_sprite.z = _vector4.z;
|
||||
_sprite.renderOrder = object.renderOrder;
|
||||
_sprite.object = object;
|
||||
|
||||
_sprite.rotation = object.rotation;
|
||||
|
@ -816,7 +799,7 @@ THREE.Projector = function () {
|
|||
var line = new THREE.RenderableLine();
|
||||
_linePool.push( line );
|
||||
_linePoolLength ++;
|
||||
_lineCount ++
|
||||
_lineCount ++;
|
||||
return line;
|
||||
|
||||
}
|
||||
|
@ -832,7 +815,7 @@ THREE.Projector = function () {
|
|||
var sprite = new THREE.RenderableSprite();
|
||||
_spritePool.push( sprite );
|
||||
_spritePoolLength ++;
|
||||
_spriteCount ++
|
||||
_spriteCount ++;
|
||||
return sprite;
|
||||
|
||||
}
|
||||
|
@ -845,7 +828,11 @@ THREE.Projector = function () {
|
|||
|
||||
function painterSort( a, b ) {
|
||||
|
||||
if ( a.z !== b.z ) {
|
||||
if ( a.renderOrder !== b.renderOrder ) {
|
||||
|
||||
return a.renderOrder - b.renderOrder;
|
||||
|
||||
} else if ( a.z !== b.z ) {
|
||||
|
||||
return b.z - a.z;
|
||||
|
||||
|
|
1579
js/libraries/three/three.min.js
vendored
1579
js/libraries/three/three.min.js
vendored
File diff suppressed because one or more lines are too long
49
js/model.js
49
js/model.js
|
@ -2,27 +2,30 @@
|
|||
|
||||
// generate mixer
|
||||
var mixerList = [
|
||||
{name: 'Tricopter', model: 'tricopter', image: 'tri'},
|
||||
{name: 'Quad +', model: 'quad_x', image: 'quad_p'},
|
||||
{name: 'Quad X', model: 'quad_x', image: 'quad_x'},
|
||||
{name: 'Bicopter', model: 'custom', image: 'bicopter'},
|
||||
{name: 'Gimbal', model: 'custom', image: 'custom'},
|
||||
{name: 'Y6', model: 'y6', image: 'y6'},
|
||||
{name: 'Hex +', model: 'hex_plus', image: 'hex_p'},
|
||||
{name: 'Flying Wing', model: 'custom', image: 'flying_wing'},
|
||||
{name: 'Y4', model: 'y4', image: 'y4'},
|
||||
{name: 'Hex X', model: 'hex_x', image: 'hex_x'},
|
||||
{name: 'Octo X8', model: 'custom', image: 'octo_x8'},
|
||||
{name: 'Octo Flat +', model: 'custom', image: 'octo_flat_p'},
|
||||
{name: 'Octo Flat X', model: 'custom', image: 'octo_flat_x'},
|
||||
{name: 'Airplane', model: 'custom', image: 'airplane'},
|
||||
{name: 'Heli 120', model: 'custom', image: 'custom'},
|
||||
{name: 'Heli 90', model: 'custom', image: 'custom'},
|
||||
{name: 'V-tail Quad', model: 'quad_vtail', image: 'vtail_quad'},
|
||||
{name: 'Hex H', model: 'custom', image: 'custom'},
|
||||
{name: 'PPM to SERVO', model: 'custom', image: 'custom'},
|
||||
{name: 'Dualcopter', model: 'custom', image: 'custom'},
|
||||
{name: 'Singlecopter', model: 'custom', image: 'custom'},
|
||||
{name: 'A-tail Quad', model: 'quad_atail', image: 'atail_quad'},
|
||||
{name: 'Custom', model: 'custom', image: 'custom'}
|
||||
{name: 'Tricopter', model: 'tricopter', image: 'tri'},
|
||||
{name: 'Quad +', model: 'quad_x', image: 'quad_p'},
|
||||
{name: 'Quad X', model: 'quad_x', image: 'quad_x'},
|
||||
{name: 'Bicopter', model: 'custom', image: 'bicopter'},
|
||||
{name: 'Gimbal', model: 'custom', image: 'custom'},
|
||||
{name: 'Y6', model: 'y6', image: 'y6'},
|
||||
{name: 'Hex +', model: 'hex_plus', image: 'hex_p'},
|
||||
{name: 'Flying Wing', model: 'custom', image: 'flying_wing'},
|
||||
{name: 'Y4', model: 'y4', image: 'y4'},
|
||||
{name: 'Hex X', model: 'hex_x', image: 'hex_x'},
|
||||
{name: 'Octo X8', model: 'custom', image: 'octo_x8'},
|
||||
{name: 'Octo Flat +', model: 'custom', image: 'octo_flat_p'},
|
||||
{name: 'Octo Flat X', model: 'custom', image: 'octo_flat_x'},
|
||||
{name: 'Airplane', model: 'custom', image: 'airplane'},
|
||||
{name: 'Heli 120', model: 'custom', image: 'custom'},
|
||||
{name: 'Heli 90', model: 'custom', image: 'custom'},
|
||||
{name: 'V-tail Quad', model: 'quad_vtail', image: 'vtail_quad'},
|
||||
{name: 'Hex H', model: 'custom', image: 'custom'},
|
||||
{name: 'PPM to SERVO', model: 'custom', image: 'custom'},
|
||||
{name: 'Dualcopter', model: 'custom', image: 'custom'},
|
||||
{name: 'Singlecopter', model: 'custom', image: 'custom'},
|
||||
{name: 'A-tail Quad', model: 'quad_atail', image: 'atail_quad'},
|
||||
{name: 'Custom', model: 'custom', image: 'custom'},
|
||||
{name: 'Custom Airplane', model: 'custom', image: 'custom'},
|
||||
{name: 'Custom Tricopter', model: 'custom', image: 'custom'}
|
||||
|
||||
];
|
||||
|
|
280
js/msp.js
280
js/msp.js
|
@ -51,7 +51,7 @@ var MSP_codes = {
|
|||
MSP_PIDNAMES: 117,
|
||||
MSP_WP: 118,
|
||||
MSP_BOXIDS: 119,
|
||||
MSP_SERVO_CONF: 120,
|
||||
MSP_SERVO_CONFIGURATIONS: 120,
|
||||
|
||||
MSP_SET_RAW_RC: 200,
|
||||
MSP_SET_RAW_GPS: 201,
|
||||
|
@ -65,10 +65,13 @@ var MSP_codes = {
|
|||
MSP_SET_WP: 209,
|
||||
MSP_SELECT_SETTING: 210,
|
||||
MSP_SET_HEAD: 211,
|
||||
MSP_SET_SERVO_CONF: 212,
|
||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||
MSP_SET_MOTOR: 214,
|
||||
|
||||
// MSP_BIND: 240,
|
||||
|
||||
MSP_SERVO_MIX_RULES: 241,
|
||||
MSP_SET_SERVO_MIX_RULE: 242,
|
||||
|
||||
MSP_EEPROM_WRITE: 250,
|
||||
|
||||
|
@ -80,7 +83,7 @@ var MSP_codes = {
|
|||
MSP_ACC_TRIM: 240, // get acc angle trim values
|
||||
MSP_SET_ACC_TRIM: 239, // set acc angle trim values
|
||||
MSP_GPS_SV_INFO: 164, // get Signal Strength
|
||||
|
||||
|
||||
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
||||
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
|
||||
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
|
||||
|
@ -102,6 +105,7 @@ var MSP = {
|
|||
|
||||
callbacks: [],
|
||||
packet_error: 0,
|
||||
unsupported: 0,
|
||||
|
||||
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
|
||||
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c'], // in LSB bit order
|
||||
|
@ -138,10 +142,14 @@ var MSP = {
|
|||
}
|
||||
break;
|
||||
case 2: // direction (should be >)
|
||||
this.unsupported = 0;
|
||||
if (data[i] == 62) { // >
|
||||
this.message_direction = 1;
|
||||
} else { // <
|
||||
} else if (data[i] == 60) { // <
|
||||
this.message_direction = 0;
|
||||
} else if (data[i] == 33) { // !
|
||||
// FC reports unsupported message error
|
||||
this.unsupported = 1;
|
||||
}
|
||||
|
||||
this.state++;
|
||||
|
@ -202,7 +210,7 @@ var MSP = {
|
|||
process_data: function (code, message_buffer, message_length) {
|
||||
var data = new DataView(message_buffer, 0); // DataView (allowing us to view arrayBuffer as struct/union)
|
||||
|
||||
switch (code) {
|
||||
if (!this.unsupported) switch (code) {
|
||||
case MSP_codes.MSP_IDENT:
|
||||
console.log('Using deprecated msp command: MSP_IDENT');
|
||||
// Deprecated
|
||||
|
@ -444,19 +452,52 @@ var MSP = {
|
|||
AUX_CONFIG_IDS.push(data.getUint8(i));
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SERVO_CONF:
|
||||
case MSP_codes.MSP_SERVO_MIX_RULES:
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_SERVO_CONFIGURATIONS:
|
||||
SERVO_CONFIG = []; // empty the array as new data is coming in
|
||||
|
||||
if (data.byteLength % 7 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 7) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
|
||||
if (data.byteLength % 14 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 14) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': data.getInt8(i + 7),
|
||||
'angleAtMax': data.getInt8(i + 8),
|
||||
'indexOfChannelToForward': data.getInt8(i + 9),
|
||||
'reversedInputSources': data.getUint32(i + 10)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (data.byteLength % 7 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 7) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': 90,
|
||||
'angleAtMax': 90,
|
||||
'indexOfChannelToForward': undefined,
|
||||
'reversedInputSources': 0
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
|
||||
if (semver.eq(CONFIG.apiVersion, '1.10.0')) {
|
||||
// drop two unused servo configurations due to MSP rx buffer to small)
|
||||
while (SERVO_CONFIG.length > 8) {
|
||||
SERVO_CONFIG.pop();
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -490,7 +531,7 @@ var MSP = {
|
|||
case MSP_codes.MSP_SELECT_SETTING:
|
||||
console.log('Profile selected');
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
case MSP_codes.MSP_SET_SERVO_CONFIGURATION:
|
||||
console.log('Servo Configuration saved');
|
||||
break;
|
||||
case MSP_codes.MSP_EEPROM_WRITE:
|
||||
|
@ -798,6 +839,8 @@ var MSP = {
|
|||
|
||||
default:
|
||||
console.log('Unknown code detected: ' + code);
|
||||
} else {
|
||||
console.log('FC reports unsupported message error: ' + code);
|
||||
}
|
||||
|
||||
// trigger callbacks, cleanup/remove callback after trigger
|
||||
|
@ -944,43 +987,43 @@ MSP.crunch = function (code) {
|
|||
case 7:
|
||||
case 8:
|
||||
case 9:
|
||||
buffer.push(parseInt(PIDs[i][0] * 10));
|
||||
buffer.push(parseInt(PIDs[i][1] * 1000));
|
||||
buffer.push(Math.round(PIDs[i][0] * 10));
|
||||
buffer.push(Math.round(PIDs[i][1] * 1000));
|
||||
buffer.push(parseInt(PIDs[i][2]));
|
||||
break;
|
||||
case 4:
|
||||
buffer.push(parseInt(PIDs[i][0] * 100));
|
||||
buffer.push(parseInt(PIDs[i][1] * 100));
|
||||
buffer.push(Math.round(PIDs[i][0] * 100));
|
||||
buffer.push(Math.round(PIDs[i][1] * 100));
|
||||
buffer.push(parseInt(PIDs[i][2]));
|
||||
break;
|
||||
case 5:
|
||||
case 6:
|
||||
buffer.push(parseInt(PIDs[i][0] * 10));
|
||||
buffer.push(parseInt(PIDs[i][1] * 100));
|
||||
buffer.push(parseInt(PIDs[i][2] * 1000));
|
||||
buffer.push(Math.round(PIDs[i][0] * 10));
|
||||
buffer.push(Math.round(PIDs[i][1] * 100));
|
||||
buffer.push(Math.round(PIDs[i][2] * 1000));
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_RC_TUNING:
|
||||
buffer.push(parseInt(RC_tuning.RC_RATE * 100));
|
||||
buffer.push(parseInt(RC_tuning.RC_EXPO * 100));
|
||||
buffer.push(Math.round(RC_tuning.RC_RATE * 100));
|
||||
buffer.push(Math.round(RC_tuning.RC_EXPO * 100));
|
||||
if (semver.lt(CONFIG.apiVersion, "1.7.0")) {
|
||||
buffer.push(parseInt(RC_tuning.roll_pitch_rate * 100));
|
||||
buffer.push(Math.round(RC_tuning.roll_pitch_rate * 100));
|
||||
} else {
|
||||
buffer.push(parseInt(RC_tuning.roll_rate * 100));
|
||||
buffer.push(parseInt(RC_tuning.pitch_rate * 100));
|
||||
buffer.push(Math.round(RC_tuning.roll_rate * 100));
|
||||
buffer.push(Math.round(RC_tuning.pitch_rate * 100));
|
||||
}
|
||||
buffer.push(parseInt(RC_tuning.yaw_rate * 100));
|
||||
buffer.push(parseInt(RC_tuning.dynamic_THR_PID * 100));
|
||||
buffer.push(parseInt(RC_tuning.throttle_MID * 100));
|
||||
buffer.push(parseInt(RC_tuning.throttle_EXPO * 100));
|
||||
buffer.push(Math.round(RC_tuning.yaw_rate * 100));
|
||||
buffer.push(Math.round(RC_tuning.dynamic_THR_PID * 100));
|
||||
buffer.push(Math.round(RC_tuning.throttle_MID * 100));
|
||||
buffer.push(Math.round(RC_tuning.throttle_EXPO * 100));
|
||||
if (semver.gte(CONFIG.apiVersion, "1.7.0")) {
|
||||
buffer.push(lowByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(highByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
|
||||
buffer.push(parseInt(RC_tuning.RC_YAW_EXPO * 100));
|
||||
buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
|
||||
}
|
||||
break;
|
||||
// Disabled, cleanflight does not use MSP_SET_BOX.
|
||||
|
@ -1028,26 +1071,12 @@ MSP.crunch = function (code) {
|
|||
buffer.push(MISC.multiwiicurrentoutput);
|
||||
buffer.push(MISC.rssi_channel);
|
||||
buffer.push(MISC.placeholder2);
|
||||
buffer.push(lowByte(MISC.mag_declination * 10));
|
||||
buffer.push(highByte(MISC.mag_declination * 10));
|
||||
buffer.push(lowByte(Math.round(MISC.mag_declination * 10)));
|
||||
buffer.push(highByte(Math.round(MISC.mag_declination * 10)));
|
||||
buffer.push(MISC.vbatscale);
|
||||
buffer.push(MISC.vbatmincellvoltage * 10);
|
||||
buffer.push(MISC.vbatmaxcellvoltage * 10);
|
||||
buffer.push(MISC.vbatwarningcellvoltage * 10);
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
}
|
||||
buffer.push(Math.round(MISC.vbatmincellvoltage * 10));
|
||||
buffer.push(Math.round(MISC.vbatmaxcellvoltage * 10));
|
||||
buffer.push(Math.round(MISC.vbatwarningcellvoltage * 10));
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
|
@ -1108,6 +1137,22 @@ MSP.crunch = function (code) {
|
|||
return buffer;
|
||||
};
|
||||
|
||||
/**
|
||||
* Set raw Rx values over MSP protocol.
|
||||
*
|
||||
* Channels is an array of 16-bit unsigned integer channel values to be sent. 8 channels is probably the maximum.
|
||||
*/
|
||||
MSP.setRawRx = function(channels) {
|
||||
var buffer = [];
|
||||
|
||||
for (var i = 0; i < channels.length; i++) {
|
||||
buffer.push(specificByte(channels[i], 0));
|
||||
buffer.push(specificByte(channels[i], 1));
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_RAW_RC, buffer, false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a request to read a block of data from the dataflash at the given address and pass that address and a dataview
|
||||
* of the returned data to the given callback (or null for the data if an error occured).
|
||||
|
@ -1128,7 +1173,102 @@ MSP.dataflashRead = function(address, onDataCallback) {
|
|||
onDataCallback(address, null);
|
||||
}
|
||||
});
|
||||
} ;
|
||||
};
|
||||
|
||||
MSP.sendServoMixRules = function(onCompleteCallback) {
|
||||
// TODO implement
|
||||
onCompleteCallback();
|
||||
};
|
||||
|
||||
MSP.sendServoConfigurations = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_servo_configuration;
|
||||
|
||||
var servoIndex = 0;
|
||||
|
||||
if (SERVO_CONFIG.length == 0) {
|
||||
onCompleteCallback();
|
||||
}
|
||||
|
||||
nextFunction();
|
||||
|
||||
function send_next_servo_configuration() {
|
||||
|
||||
var buffer = [];
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
// send all in one go
|
||||
// 1.9.0 had a bug where the MSP input buffer was too small, limit to 8.
|
||||
for (var i = 0; i < SERVO_CONFIG.length && i < 8; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
}
|
||||
|
||||
nextFunction = send_channel_forwarding;
|
||||
} else {
|
||||
// send one at a time, with index
|
||||
|
||||
var servoConfiguration = SERVO_CONFIG[servoIndex];
|
||||
|
||||
buffer.push(servoIndex);
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.min));
|
||||
buffer.push(highByte(servoConfiguration.min));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.max));
|
||||
buffer.push(highByte(servoConfiguration.max));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.middle));
|
||||
buffer.push(highByte(servoConfiguration.middle));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.rate));
|
||||
|
||||
buffer.push(servoConfiguration.angleAtMin);
|
||||
buffer.push(servoConfiguration.angleAtMax);
|
||||
|
||||
var out = servoConfiguration.indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 0));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 1));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 2));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 3));
|
||||
|
||||
// prepare for next iteration
|
||||
servoIndex++;
|
||||
if (servoIndex == SERVO_CONFIG.length) {
|
||||
nextFunction = onCompleteCallback;
|
||||
}
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONFIGURATION, buffer, false, nextFunction);
|
||||
}
|
||||
|
||||
function send_channel_forwarding() {
|
||||
var buffer = [];
|
||||
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
}
|
||||
|
||||
nextFunction = onCompleteCallback;
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
MSP.sendModeRanges = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_mode_range;
|
||||
|
@ -1146,12 +1286,12 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
|
||||
var modeRange = MODE_RANGES[modeRangeIndex];
|
||||
|
||||
var AUX_val_buffer_out = [];
|
||||
AUX_val_buffer_out.push(modeRangeIndex);
|
||||
AUX_val_buffer_out.push(modeRange.id);
|
||||
AUX_val_buffer_out.push(modeRange.auxChannelIndex);
|
||||
AUX_val_buffer_out.push((modeRange.range.start - 900) / 25);
|
||||
AUX_val_buffer_out.push((modeRange.range.end - 900) / 25);
|
||||
var buffer = [];
|
||||
buffer.push(modeRangeIndex);
|
||||
buffer.push(modeRange.id);
|
||||
buffer.push(modeRange.auxChannelIndex);
|
||||
buffer.push((modeRange.range.start - 900) / 25);
|
||||
buffer.push((modeRange.range.end - 900) / 25);
|
||||
|
||||
// prepare for next iteration
|
||||
modeRangeIndex++;
|
||||
|
@ -1159,7 +1299,7 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, AUX_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1179,14 +1319,14 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
|
||||
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
|
||||
|
||||
var ADJUSTMENT_val_buffer_out = [];
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRangeIndex);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.slotIndex);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxChannelIndex);
|
||||
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.start - 900) / 25);
|
||||
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.end - 900) / 25);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.adjustmentFunction);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxSwitchChannelIndex);
|
||||
var buffer = [];
|
||||
buffer.push(adjustmentRangeIndex);
|
||||
buffer.push(adjustmentRange.slotIndex);
|
||||
buffer.push(adjustmentRange.auxChannelIndex);
|
||||
buffer.push((adjustmentRange.range.start - 900) / 25);
|
||||
buffer.push((adjustmentRange.range.end - 900) / 25);
|
||||
buffer.push(adjustmentRange.adjustmentFunction);
|
||||
buffer.push(adjustmentRange.auxSwitchChannelIndex);
|
||||
|
||||
// prepare for next iteration
|
||||
adjustmentRangeIndex++;
|
||||
|
@ -1194,7 +1334,7 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, ADJUSTMENT_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue