mirror of https://github.com/ArduPilot/ardupilot
Flight tested transmitter cal. Yaw is OK. Acro Mode OK. Flew Stable Mode OK.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@254 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
92fd459504
commit
c99be7e0ca
|
@ -49,11 +49,11 @@
|
||||||
/* User definable modules */
|
/* User definable modules */
|
||||||
|
|
||||||
// Comment out with // modules that you are not using
|
// Comment out with // modules that you are not using
|
||||||
#define IsGPS // Do we have a GPS connected
|
//#define IsGPS // Do we have a GPS connected
|
||||||
#define IsNEWMTEK// Do we have MTEK with new firmware
|
//#define IsNEWMTEK// Do we have MTEK with new firmware
|
||||||
#define IsMAG // Do we have a Magnetometer connected, if have remember to activate it from Configurator
|
#define IsMAG // Do we have a Magnetometer connected, if have remember to activate it from Configurator
|
||||||
#define IsTEL // Do we have a telemetry connected, eg. XBee connected on Telemetry port
|
//#define IsTEL // Do we have a telemetry connected, eg. XBee connected on Telemetry port
|
||||||
#define IsAM // Do we have motormount LED's. AM = Atraction Mode
|
//#define IsAM // Do we have motormount LED's. AM = Atraction Mode
|
||||||
|
|
||||||
#define CONFIGURATOR // Do se use Configurator or normal text output over serial link
|
#define CONFIGURATOR // Do se use Configurator or normal text output over serial link
|
||||||
|
|
||||||
|
@ -72,8 +72,8 @@
|
||||||
/* User definable modules - END */
|
/* User definable modules - END */
|
||||||
|
|
||||||
// Frame build condiguration
|
// Frame build condiguration
|
||||||
#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
//#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
||||||
//#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
||||||
|
|
||||||
|
|
||||||
/* ****************************************************************************** */
|
/* ****************************************************************************** */
|
||||||
|
@ -500,10 +500,10 @@ void loop(){
|
||||||
{
|
{
|
||||||
// Commands from radio Rx...
|
// Commands from radio Rx...
|
||||||
// Stick position defines the desired angle in roll, pitch and yaw
|
// Stick position defines the desired angle in roll, pitch and yaw
|
||||||
ch_roll = channel_filter(APM_RC.InputCh(0), ch_roll) * ch_roll_slope + ch_roll_offset;
|
ch_roll = channel_filter(APM_RC.InputCh(0) * ch_roll_slope + ch_roll_offset, ch_roll);
|
||||||
ch_pitch = channel_filter(APM_RC.InputCh(1), ch_pitch) * ch_pitch_slope + ch_pitch_offset;
|
ch_pitch = channel_filter(APM_RC.InputCh(1) * ch_pitch_slope + ch_pitch_offset, ch_pitch);
|
||||||
ch_throttle = channel_filter(APM_RC.InputCh(2), ch_throttle) * ch_throttle_slope + ch_throttle_offset;
|
ch_throttle = channel_filter(APM_RC.InputCh(2) * ch_throttle_slope + ch_throttle_offset, ch_throttle);
|
||||||
ch_yaw = channel_filter(APM_RC.InputCh(3), ch_yaw) * ch_yaw_slope + ch_yaw_offset;
|
ch_yaw = channel_filter(APM_RC.InputCh(3) * ch_yaw_slope + ch_yaw_offset, ch_yaw);
|
||||||
ch_aux = APM_RC.InputCh(4) * ch_aux_slope + ch_aux_offset;
|
ch_aux = APM_RC.InputCh(4) * ch_aux_slope + ch_aux_offset;
|
||||||
ch_aux2 = APM_RC.InputCh(5) * ch_aux2_slope + ch_aux2_offset;
|
ch_aux2 = APM_RC.InputCh(5) * ch_aux2_slope + ch_aux2_offset;
|
||||||
command_rx_roll_old = command_rx_roll;
|
command_rx_roll_old = command_rx_roll;
|
||||||
|
@ -740,4 +740,4 @@ void loop(){
|
||||||
// END of Arducopter.pde
|
// END of Arducopter.pde
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -87,54 +87,10 @@ void readSerialCommand() {
|
||||||
xmitFactor = readFloatSerial();
|
xmitFactor = readFloatSerial();
|
||||||
break;
|
break;
|
||||||
case 'W': // Write all user configurable values to EEPROM
|
case 'W': // Write all user configurable values to EEPROM
|
||||||
writeEEPROM(KP_QUAD_ROLL, KP_QUAD_ROLL_ADR);
|
writeUserConfig();
|
||||||
writeEEPROM(KD_QUAD_ROLL, KD_QUAD_ROLL_ADR);
|
|
||||||
writeEEPROM(KI_QUAD_ROLL, KI_QUAD_ROLL_ADR);
|
|
||||||
writeEEPROM(KP_QUAD_PITCH, KP_QUAD_PITCH_ADR);
|
|
||||||
writeEEPROM(KD_QUAD_PITCH, KD_QUAD_PITCH_ADR);
|
|
||||||
writeEEPROM(KI_QUAD_PITCH, KI_QUAD_PITCH_ADR);
|
|
||||||
writeEEPROM(KP_QUAD_YAW, KP_QUAD_YAW_ADR);
|
|
||||||
writeEEPROM(KD_QUAD_YAW, KD_QUAD_YAW_ADR);
|
|
||||||
writeEEPROM(KI_QUAD_YAW, KI_QUAD_YAW_ADR);
|
|
||||||
writeEEPROM(STABLE_MODE_KP_RATE, STABLE_MODE_KP_RATE_ADR);
|
|
||||||
writeEEPROM(KP_GPS_ROLL, KP_GPS_ROLL_ADR);
|
|
||||||
writeEEPROM(KD_GPS_ROLL, KD_GPS_ROLL_ADR);
|
|
||||||
writeEEPROM(KI_GPS_ROLL, KI_GPS_ROLL_ADR);
|
|
||||||
writeEEPROM(KP_GPS_PITCH, KP_GPS_PITCH_ADR);
|
|
||||||
writeEEPROM(KD_GPS_PITCH, KD_GPS_PITCH_ADR);
|
|
||||||
writeEEPROM(KI_GPS_PITCH, KI_GPS_PITCH_ADR);
|
|
||||||
writeEEPROM(GPS_MAX_ANGLE, GPS_MAX_ANGLE_ADR);
|
|
||||||
writeEEPROM(KP_ALTITUDE, KP_ALTITUDE_ADR);
|
|
||||||
writeEEPROM(KD_ALTITUDE, KD_ALTITUDE_ADR);
|
|
||||||
writeEEPROM(KI_ALTITUDE, KI_ALTITUDE_ADR);
|
|
||||||
writeEEPROM(acc_offset_x, acc_offset_x_ADR);
|
|
||||||
writeEEPROM(acc_offset_y, acc_offset_y_ADR);
|
|
||||||
writeEEPROM(acc_offset_z, acc_offset_z_ADR);
|
|
||||||
writeEEPROM(gyro_offset_roll, gyro_offset_roll_ADR);
|
|
||||||
writeEEPROM(gyro_offset_pitch, gyro_offset_pitch_ADR);
|
|
||||||
writeEEPROM(gyro_offset_yaw, gyro_offset_yaw_ADR);
|
|
||||||
writeEEPROM(Kp_ROLLPITCH, Kp_ROLLPITCH_ADR);
|
|
||||||
writeEEPROM(Ki_ROLLPITCH, Ki_ROLLPITCH_ADR);
|
|
||||||
writeEEPROM(Kp_YAW, Kp_YAW_ADR);
|
|
||||||
writeEEPROM(Ki_YAW, Ki_YAW_ADR);
|
|
||||||
writeEEPROM(GEOG_CORRECTION_FACTOR, GEOG_CORRECTION_FACTOR_ADR);
|
|
||||||
writeEEPROM(MAGNETOMETER, MAGNETOMETER_ADR);
|
|
||||||
writeEEPROM(Kp_RateRoll, KP_RATEROLL_ADR);
|
|
||||||
writeEEPROM(Ki_RateRoll, KI_RATEROLL_ADR);
|
|
||||||
writeEEPROM(Kd_RateRoll, KD_RATEROLL_ADR);
|
|
||||||
writeEEPROM(Kp_RatePitch, KP_RATEPITCH_ADR);
|
|
||||||
writeEEPROM(Ki_RatePitch, KI_RATEPITCH_ADR);
|
|
||||||
writeEEPROM(Kd_RatePitch, KD_RATEPITCH_ADR);
|
|
||||||
writeEEPROM(Kp_RateYaw, KP_RATEYAW_ADR);
|
|
||||||
writeEEPROM(Ki_RateYaw, KI_RATEYAW_ADR);
|
|
||||||
writeEEPROM(Kd_RateYaw, KD_RATEYAW_ADR);
|
|
||||||
writeEEPROM(xmitFactor, XMITFACTOR_ADR);
|
|
||||||
writeEEPROM(roll_mid, CHROLL_MID);
|
|
||||||
writeEEPROM(pitch_mid, CHPITCH_MID);
|
|
||||||
writeEEPROM(yaw_mid, CHYAW_MID);
|
|
||||||
break;
|
break;
|
||||||
case 'Y': // Initialize EEPROM with default values
|
case 'Y': // Initialize EEPROM with default values
|
||||||
setUserConfig();
|
defaultUserConfig();
|
||||||
break;
|
break;
|
||||||
case '1': // Receive transmitter calibration values
|
case '1': // Receive transmitter calibration values
|
||||||
ch_roll_slope = readFloatSerial();
|
ch_roll_slope = readFloatSerial();
|
||||||
|
@ -158,7 +114,7 @@ void sendSerialTelemetry() {
|
||||||
float aux_float[3]; // used for sensor calibration
|
float aux_float[3]; // used for sensor calibration
|
||||||
switch (queryType) {
|
switch (queryType) {
|
||||||
case '=': // Reserved debug command to view any variable from Serial Monitor
|
case '=': // Reserved debug command to view any variable from Serial Monitor
|
||||||
Serial.print("throttle =");
|
/* Serial.print("throttle =");
|
||||||
Serial.println(ch_throttle);
|
Serial.println(ch_throttle);
|
||||||
Serial.print("control roll =");
|
Serial.print("control roll =");
|
||||||
Serial.println(control_roll-CHANN_CENTER);
|
Serial.println(control_roll-CHANN_CENTER);
|
||||||
|
@ -185,7 +141,14 @@ void sendSerialTelemetry() {
|
||||||
Serial.print("command rx yaw =");
|
Serial.print("command rx yaw =");
|
||||||
Serial.println(command_rx_yaw);
|
Serial.println(command_rx_yaw);
|
||||||
Serial.println();
|
Serial.println();
|
||||||
queryType = 'X';
|
queryType = 'X';*/
|
||||||
|
Serial.print(APM_RC.InputCh(0));
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_roll_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_roll_offset);
|
||||||
|
comma();
|
||||||
|
Serial.println(ch_roll);
|
||||||
break;
|
break;
|
||||||
case 'B': // Send roll, pitch and yaw PID values
|
case 'B': // Send roll, pitch and yaw PID values
|
||||||
Serial.print(KP_QUAD_ROLL, 3);
|
Serial.print(KP_QUAD_ROLL, 3);
|
||||||
|
@ -310,9 +273,9 @@ void sendSerialTelemetry() {
|
||||||
comma();
|
comma();
|
||||||
Serial.print(err_pitch);
|
Serial.print(err_pitch);
|
||||||
comma();
|
comma();
|
||||||
Serial.print(degrees(-roll));
|
Serial.print(degrees(roll));
|
||||||
comma();
|
comma();
|
||||||
Serial.print(degrees(-pitch));
|
Serial.print(degrees(pitch));
|
||||||
comma();
|
comma();
|
||||||
Serial.println(degrees(yaw));
|
Serial.println(degrees(yaw));
|
||||||
break;
|
break;
|
||||||
|
@ -378,6 +341,32 @@ void sendSerialTelemetry() {
|
||||||
Serial.println(VER);
|
Serial.println(VER);
|
||||||
queryType = 'X';
|
queryType = 'X';
|
||||||
break;
|
break;
|
||||||
|
case '2': // Send transmitter calibration values
|
||||||
|
Serial.print(ch_roll_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_roll_offset);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_pitch_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_pitch_offset);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_yaw_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_yaw_offset);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_throttle_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_throttle_offset);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_aux_slope);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_aux_offset);
|
||||||
|
comma();
|
||||||
|
Serial.print(ch_aux2_slope);
|
||||||
|
comma();
|
||||||
|
Serial.println(ch_aux2_offset);
|
||||||
|
queryType = 'X';
|
||||||
|
break;
|
||||||
case '.': // Modify GPS settings
|
case '.': // Modify GPS settings
|
||||||
Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
|
Serial1.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
|
||||||
break;
|
break;
|
||||||
|
@ -403,4 +392,4 @@ float readFloatSerial() {
|
||||||
}
|
}
|
||||||
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
|
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
|
||||||
return atof(data);
|
return atof(data);
|
||||||
}
|
}
|
||||||
|
|
|
@ -125,7 +125,7 @@ float ch_aux2_offset = 0;
|
||||||
|
|
||||||
// This function call contains the default values that are set to the ArduCopter
|
// This function call contains the default values that are set to the ArduCopter
|
||||||
// when a "Default EEPROM Value" command is sent through serial interface
|
// when a "Default EEPROM Value" command is sent through serial interface
|
||||||
void setUserConfig() {
|
void defaultUserConfig() {
|
||||||
KP_QUAD_ROLL = 1.8;
|
KP_QUAD_ROLL = 1.8;
|
||||||
KI_QUAD_ROLL = 0.30; //0.4
|
KI_QUAD_ROLL = 0.30; //0.4
|
||||||
KD_QUAD_ROLL = 0.4; //0.48
|
KD_QUAD_ROLL = 0.4; //0.48
|
||||||
|
@ -313,10 +313,9 @@ void readUserConfig() {
|
||||||
roll_mid = readEEPROM(CHROLL_MID);
|
roll_mid = readEEPROM(CHROLL_MID);
|
||||||
pitch_mid = readEEPROM(CHPITCH_MID);
|
pitch_mid = readEEPROM(CHPITCH_MID);
|
||||||
yaw_mid = readEEPROM(CHYAW_MID);
|
yaw_mid = readEEPROM(CHYAW_MID);
|
||||||
/* uncommented for now until flight tested
|
|
||||||
ch_roll_slope = readEEPROM(ch_roll_slope_ADR);
|
ch_roll_slope = readEEPROM(ch_roll_slope_ADR);
|
||||||
ch_pitch_slope = readEEPROM(ch_pitch_slope_ADR);
|
ch_pitch_slope = readEEPROM(ch_pitch_slope_ADR);
|
||||||
ch_throttle_slope readEEPROM(ch_throttle_slope_ADR);
|
ch_throttle_slope = readEEPROM(ch_throttle_slope_ADR);
|
||||||
ch_yaw_slope = readEEPROM(ch_yaw_slope_ADR);
|
ch_yaw_slope = readEEPROM(ch_yaw_slope_ADR);
|
||||||
ch_aux_slope = readEEPROM(ch_aux_slope_ADR);
|
ch_aux_slope = readEEPROM(ch_aux_slope_ADR);
|
||||||
ch_aux2_slope = readEEPROM(ch_aux2_slope_ADR);
|
ch_aux2_slope = readEEPROM(ch_aux2_slope_ADR);
|
||||||
|
@ -325,6 +324,65 @@ void readUserConfig() {
|
||||||
ch_throttle_offset = readEEPROM(ch_throttle_offset_ADR);
|
ch_throttle_offset = readEEPROM(ch_throttle_offset_ADR);
|
||||||
ch_yaw_offset = readEEPROM(ch_yaw_offset_ADR);
|
ch_yaw_offset = readEEPROM(ch_yaw_offset_ADR);
|
||||||
ch_aux_offset = readEEPROM(ch_aux_offset_ADR);
|
ch_aux_offset = readEEPROM(ch_aux_offset_ADR);
|
||||||
ch_aux2_offset = readEEPROM(ch_aux2_offset_ADR); */
|
ch_aux2_offset = readEEPROM(ch_aux2_offset_ADR);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void writeUserConfig() {
|
||||||
|
writeEEPROM(KP_QUAD_ROLL, KP_QUAD_ROLL_ADR);
|
||||||
|
writeEEPROM(KD_QUAD_ROLL, KD_QUAD_ROLL_ADR);
|
||||||
|
writeEEPROM(KI_QUAD_ROLL, KI_QUAD_ROLL_ADR);
|
||||||
|
writeEEPROM(KP_QUAD_PITCH, KP_QUAD_PITCH_ADR);
|
||||||
|
writeEEPROM(KD_QUAD_PITCH, KD_QUAD_PITCH_ADR);
|
||||||
|
writeEEPROM(KI_QUAD_PITCH, KI_QUAD_PITCH_ADR);
|
||||||
|
writeEEPROM(KP_QUAD_YAW, KP_QUAD_YAW_ADR);
|
||||||
|
writeEEPROM(KD_QUAD_YAW, KD_QUAD_YAW_ADR);
|
||||||
|
writeEEPROM(KI_QUAD_YAW, KI_QUAD_YAW_ADR);
|
||||||
|
writeEEPROM(STABLE_MODE_KP_RATE, STABLE_MODE_KP_RATE_ADR);
|
||||||
|
writeEEPROM(KP_GPS_ROLL, KP_GPS_ROLL_ADR);
|
||||||
|
writeEEPROM(KD_GPS_ROLL, KD_GPS_ROLL_ADR);
|
||||||
|
writeEEPROM(KI_GPS_ROLL, KI_GPS_ROLL_ADR);
|
||||||
|
writeEEPROM(KP_GPS_PITCH, KP_GPS_PITCH_ADR);
|
||||||
|
writeEEPROM(KD_GPS_PITCH, KD_GPS_PITCH_ADR);
|
||||||
|
writeEEPROM(KI_GPS_PITCH, KI_GPS_PITCH_ADR);
|
||||||
|
writeEEPROM(GPS_MAX_ANGLE, GPS_MAX_ANGLE_ADR);
|
||||||
|
writeEEPROM(KP_ALTITUDE, KP_ALTITUDE_ADR);
|
||||||
|
writeEEPROM(KD_ALTITUDE, KD_ALTITUDE_ADR);
|
||||||
|
writeEEPROM(KI_ALTITUDE, KI_ALTITUDE_ADR);
|
||||||
|
writeEEPROM(acc_offset_x, acc_offset_x_ADR);
|
||||||
|
writeEEPROM(acc_offset_y, acc_offset_y_ADR);
|
||||||
|
writeEEPROM(acc_offset_z, acc_offset_z_ADR);
|
||||||
|
writeEEPROM(gyro_offset_roll, gyro_offset_roll_ADR);
|
||||||
|
writeEEPROM(gyro_offset_pitch, gyro_offset_pitch_ADR);
|
||||||
|
writeEEPROM(gyro_offset_yaw, gyro_offset_yaw_ADR);
|
||||||
|
writeEEPROM(Kp_ROLLPITCH, Kp_ROLLPITCH_ADR);
|
||||||
|
writeEEPROM(Ki_ROLLPITCH, Ki_ROLLPITCH_ADR);
|
||||||
|
writeEEPROM(Kp_YAW, Kp_YAW_ADR);
|
||||||
|
writeEEPROM(Ki_YAW, Ki_YAW_ADR);
|
||||||
|
writeEEPROM(GEOG_CORRECTION_FACTOR, GEOG_CORRECTION_FACTOR_ADR);
|
||||||
|
writeEEPROM(MAGNETOMETER, MAGNETOMETER_ADR);
|
||||||
|
writeEEPROM(Kp_RateRoll, KP_RATEROLL_ADR);
|
||||||
|
writeEEPROM(Ki_RateRoll, KI_RATEROLL_ADR);
|
||||||
|
writeEEPROM(Kd_RateRoll, KD_RATEROLL_ADR);
|
||||||
|
writeEEPROM(Kp_RatePitch, KP_RATEPITCH_ADR);
|
||||||
|
writeEEPROM(Ki_RatePitch, KI_RATEPITCH_ADR);
|
||||||
|
writeEEPROM(Kd_RatePitch, KD_RATEPITCH_ADR);
|
||||||
|
writeEEPROM(Kp_RateYaw, KP_RATEYAW_ADR);
|
||||||
|
writeEEPROM(Ki_RateYaw, KI_RATEYAW_ADR);
|
||||||
|
writeEEPROM(Kd_RateYaw, KD_RATEYAW_ADR);
|
||||||
|
writeEEPROM(xmitFactor, XMITFACTOR_ADR);
|
||||||
|
writeEEPROM(roll_mid, CHROLL_MID);
|
||||||
|
writeEEPROM(pitch_mid, CHPITCH_MID);
|
||||||
|
writeEEPROM(yaw_mid, CHYAW_MID);
|
||||||
|
writeEEPROM(ch_roll_slope, ch_roll_slope_ADR);
|
||||||
|
writeEEPROM(ch_pitch_slope, ch_pitch_slope_ADR);
|
||||||
|
writeEEPROM(ch_throttle_slope, ch_throttle_slope_ADR);
|
||||||
|
writeEEPROM(ch_yaw_slope, ch_yaw_slope_ADR);
|
||||||
|
writeEEPROM(ch_aux_slope, ch_aux_slope_ADR);
|
||||||
|
writeEEPROM(ch_aux2_slope, ch_aux2_slope_ADR);
|
||||||
|
writeEEPROM(ch_roll_offset, ch_roll_offset_ADR);
|
||||||
|
writeEEPROM(ch_pitch_offset, ch_pitch_offset_ADR);
|
||||||
|
writeEEPROM(ch_throttle_offset, ch_throttle_offset_ADR);
|
||||||
|
writeEEPROM(ch_yaw_offset, ch_yaw_offset_ADR);
|
||||||
|
writeEEPROM(ch_aux_offset, ch_aux_offset_ADR);
|
||||||
|
writeEEPROM(ch_aux2_offset, ch_aux2_offset_ADR);
|
||||||
|
}
|
||||||
|
|
|
@ -10,6 +10,6 @@ DebugServerWaitOnLaunch = False
|
||||||
useLocaleDecimalPt = False
|
useLocaleDecimalPt = False
|
||||||
|
|
||||||
[Configuration]
|
[Configuration]
|
||||||
COMport = "COM10"
|
COMport = "COM13"
|
||||||
Timeout = 10
|
Timeout = 10
|
||||||
Baud = 115200
|
Baud = 115200
|
|
@ -122,7 +122,7 @@
|
||||||
<Item Name="kernel32.dll" Type="Document" URL="kernel32.dll">
|
<Item Name="kernel32.dll" Type="Document" URL="kernel32.dll">
|
||||||
<Property Name="NI.PreserveRelativePath" Type="Bool">true</Property>
|
<Property Name="NI.PreserveRelativePath" Type="Bool">true</Property>
|
||||||
</Item>
|
</Item>
|
||||||
<Item Name="lvanlys.dll" Type="Document" URL="../../../../../../../../Program Files (x86)/National Instruments/LabVIEW 2009/resource/lvanlys.dll"/>
|
<Item Name="lvanlys.dll" Type="Document" URL="../../../../../../../../Program Files/National Instruments/LabVIEW 2009/resource/lvanlys.dll"/>
|
||||||
</Item>
|
</Item>
|
||||||
<Item Name="Build Specifications" Type="Build">
|
<Item Name="Build Specifications" Type="Build">
|
||||||
<Item Name="Executable" Type="EXE">
|
<Item Name="Executable" Type="EXE">
|
||||||
|
|
Binary file not shown.
Loading…
Reference in New Issue