mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
Conflicts: Tools/autotest/autotest.py
This commit is contained in:
commit
3b825fb8c1
@ -75,7 +75,8 @@ public:
|
||||
k_param_heli_collective_mid,
|
||||
k_param_heli_ext_gyro_enabled,
|
||||
k_param_heli_ext_gyro_gain,
|
||||
k_param_heli_servo_averaging, // 94
|
||||
k_param_heli_servo_averaging,
|
||||
k_param_heli_servo_manual, // 95
|
||||
#endif
|
||||
|
||||
// 110: Telemetry control
|
||||
@ -253,6 +254,7 @@ public:
|
||||
AP_Int8 heli_ext_gyro_enabled; // 0 = no external tail gyro, 1 = external tail gyro
|
||||
AP_Int16 heli_ext_gyro_gain; // radio output 1000~2000 (value output on CH_7)
|
||||
AP_Int8 heli_servo_averaging; // 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
|
||||
AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
|
||||
#endif
|
||||
|
||||
// RC channels
|
||||
@ -320,7 +322,7 @@ public:
|
||||
command_index (0, k_param_command_index, PSTR("WP_INDEX")),
|
||||
command_must_index (0, k_param_command_must_index, PSTR("WP_MUST_INDEX")),
|
||||
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
|
||||
loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
|
||||
loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
|
||||
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
|
||||
|
||||
throttle_min (0, k_param_throttle_min, PSTR("THR_MIN")),
|
||||
@ -361,6 +363,7 @@ public:
|
||||
heli_ext_gyro_enabled (0, k_param_heli_ext_gyro_enabled, PSTR("GYR_ENABLE_")),
|
||||
heli_ext_gyro_gain (1000, k_param_heli_ext_gyro_gain, PSTR("GYR_GAIN_")),
|
||||
heli_servo_averaging (0, k_param_heli_servo_averaging, PSTR("SV_AVG")),
|
||||
heli_servo_manual (0, k_param_heli_servo_manual, PSTR("HSV_MAN")),
|
||||
#endif
|
||||
|
||||
// RC channel group key name
|
||||
|
@ -5,7 +5,6 @@
|
||||
#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz
|
||||
#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz
|
||||
|
||||
static int heli_manual_override = false;
|
||||
static float heli_throttle_scaler = 0;
|
||||
|
||||
// heli_servo_averaging:
|
||||
@ -81,25 +80,18 @@ static void heli_move_servos_to_mid()
|
||||
// yaw: -4500 ~ 4500
|
||||
//
|
||||
static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
|
||||
{
|
||||
{
|
||||
// ensure values are acceptable:
|
||||
roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
|
||||
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
|
||||
coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max);
|
||||
if( g.heli_servo_manual != 1) {
|
||||
roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
|
||||
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
|
||||
coll_out = constrain(coll_out, (int)g.heli_coll_min, (int)g.heli_coll_max);
|
||||
}
|
||||
|
||||
// swashplate servos
|
||||
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out + (g.heli_servo_1.radio_trim-1500);
|
||||
if( g.heli_servo_1.get_reverse() )
|
||||
g.heli_servo_1.servo_out = 3000 - g.heli_servo_1.servo_out;
|
||||
|
||||
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out + (g.heli_servo_2.radio_trim-1500);
|
||||
if( g.heli_servo_2.get_reverse() )
|
||||
g.heli_servo_2.servo_out = 3000 - g.heli_servo_2.servo_out;
|
||||
|
||||
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out + (g.heli_servo_3.radio_trim-1500);
|
||||
if( g.heli_servo_3.get_reverse() )
|
||||
g.heli_servo_3.servo_out = 3000 - g.heli_servo_3.servo_out;
|
||||
|
||||
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_1.radio_trim-1500);
|
||||
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_2.radio_trim-1500);
|
||||
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out - 1000 + (g.heli_servo_3.radio_trim-1500);
|
||||
g.heli_servo_4.servo_out = yaw_out;
|
||||
|
||||
// use servo_out to calculate pwm_out and radio_out
|
||||
@ -109,9 +101,9 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||
g.heli_servo_4.calc_pwm();
|
||||
|
||||
// add the servo values to the averaging
|
||||
heli_servo_out[0] += g.heli_servo_1.servo_out;
|
||||
heli_servo_out[1] += g.heli_servo_2.servo_out;
|
||||
heli_servo_out[2] += g.heli_servo_3.servo_out;
|
||||
heli_servo_out[0] += g.heli_servo_1.radio_out;
|
||||
heli_servo_out[1] += g.heli_servo_2.radio_out;
|
||||
heli_servo_out[2] += g.heli_servo_3.radio_out;
|
||||
heli_servo_out[3] += g.heli_servo_4.radio_out;
|
||||
heli_servo_out_count++;
|
||||
|
||||
@ -125,13 +117,13 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||
heli_servo_out[2] /= g.heli_servo_averaging;
|
||||
heli_servo_out[3] /= g.heli_servo_averaging;
|
||||
}
|
||||
|
||||
|
||||
// actually move the servos
|
||||
APM_RC.OutputCh(CH_1, heli_servo_out[0]);
|
||||
APM_RC.OutputCh(CH_2, heli_servo_out[1]);
|
||||
APM_RC.OutputCh(CH_3, heli_servo_out[2]);
|
||||
APM_RC.OutputCh(CH_4, heli_servo_out[3]);
|
||||
|
||||
|
||||
// output gyro value
|
||||
if( g.heli_ext_gyro_enabled ) {
|
||||
APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
|
||||
@ -164,19 +156,21 @@ static void init_motors_out()
|
||||
// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
|
||||
static void output_motors_armed()
|
||||
{
|
||||
// if manual override (i.e. when setting up swash), pass pilot commands straight through to swash
|
||||
if( g.heli_servo_manual == 1 ) {
|
||||
g.rc_1.servo_out = g.rc_1.control_in;
|
||||
g.rc_2.servo_out = g.rc_2.control_in;
|
||||
g.rc_3.servo_out = g.rc_3.control_in;
|
||||
g.rc_4.servo_out = g.rc_4.control_in;
|
||||
}
|
||||
|
||||
//static int counter = 0;
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
if( heli_manual_override ) {
|
||||
// straight pass through from radio inputs to swash plate
|
||||
heli_move_swash( g.rc_1.control_in, g.rc_2.control_in, g.rc_3.radio_in, g.rc_4.control_in );
|
||||
}else{
|
||||
// source inputs from attitude controller
|
||||
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out );
|
||||
}
|
||||
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.radio_out, g.rc_4.servo_out );
|
||||
}
|
||||
|
||||
// for helis - armed or disarmed we allow servos to move
|
||||
@ -200,7 +194,7 @@ static void output_motor_test()
|
||||
static int heli_get_scaled_throttle(int throttle)
|
||||
{
|
||||
float scaled_throttle = (g.heli_coll_min - 1000) + throttle * heli_throttle_scaler;
|
||||
return g.heli_coll_min - 1000 + (throttle * heli_throttle_scaler);
|
||||
return scaled_throttle;
|
||||
}
|
||||
|
||||
// heli_angle_boost - takes servo_out position
|
||||
|
@ -9,8 +9,8 @@ static void default_dead_zones()
|
||||
g.rc_1.set_dead_zone(60);
|
||||
g.rc_2.set_dead_zone(60);
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
g.rc_3.set_dead_zone(0);
|
||||
g.rc_4.set_dead_zone(60);
|
||||
g.rc_3.set_dead_zone(20);
|
||||
g.rc_4.set_dead_zone(30);
|
||||
#else
|
||||
g.rc_3.set_dead_zone(60);
|
||||
g.rc_4.set_dead_zone(200);
|
||||
|
@ -469,8 +469,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
// initialise swash plate
|
||||
heli_init_swash();
|
||||
|
||||
// source swash plate movements directly from
|
||||
heli_manual_override = true;
|
||||
// source swash plate movements directly from radio
|
||||
g.heli_servo_manual = true;
|
||||
|
||||
// display initial settings
|
||||
report_heli();
|
||||
@ -494,6 +494,9 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
|
||||
// read radio although we don't use it yet
|
||||
read_radio();
|
||||
|
||||
// allow swash plate to move
|
||||
output_motors_armed();
|
||||
|
||||
// record min/max
|
||||
if( state == 1 ) {
|
||||
@ -501,13 +504,12 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
max_roll = abs(g.rc_1.control_in);
|
||||
if( abs(g.rc_2.control_in) > max_pitch )
|
||||
max_pitch = abs(g.rc_2.control_in);
|
||||
if( g.rc_3.radio_in < min_coll )
|
||||
min_coll = g.rc_3.radio_in;
|
||||
if( g.rc_3.radio_in > max_coll )
|
||||
max_coll = g.rc_3.radio_in;
|
||||
min_tail = min(g.rc_4.radio_in, min_tail);
|
||||
max_tail = max(g.rc_4.radio_in, max_tail);
|
||||
//Serial.printf_P(PSTR("4: ri:%d \tro:%d \tso:%d \n"), (int)g.rc_4.radio_in, (int)g.rc_4.radio_out, (int)g.rc_4.servo_out);
|
||||
if( g.rc_3.radio_out < min_coll )
|
||||
min_coll = g.rc_3.radio_out;
|
||||
if( g.rc_3.radio_out > max_coll )
|
||||
max_coll = g.rc_3.radio_out;
|
||||
min_tail = min(g.rc_4.radio_out, min_tail);
|
||||
max_tail = max(g.rc_4.radio_out, max_tail);
|
||||
}
|
||||
|
||||
if( Serial.available() ) {
|
||||
@ -533,8 +535,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
break;
|
||||
case 'c':
|
||||
case 'C':
|
||||
if( g.rc_3.radio_in >= 900 && g.rc_3.radio_in <= 2100 ) {
|
||||
g.heli_coll_mid = g.rc_3.radio_in;
|
||||
if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) {
|
||||
g.heli_coll_mid = g.rc_3.radio_out;
|
||||
Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_coll_mid);
|
||||
}
|
||||
break;
|
||||
@ -561,7 +563,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
max_pitch = abs(g.rc_2.control_in);
|
||||
min_coll = 2000;
|
||||
max_coll = 1000;
|
||||
min_tail = max_tail = abs(g.rc_4.radio_in);
|
||||
min_tail = max_tail = abs(g.rc_4.radio_out);
|
||||
}else{
|
||||
state = 0; // switch back to normal mode
|
||||
// double check values aren't totally terrible
|
||||
@ -639,9 +641,6 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
}
|
||||
|
||||
// allow swash plate to move
|
||||
output_motors_armed();
|
||||
|
||||
delay(20);
|
||||
}
|
||||
|
||||
@ -664,7 +663,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
g.heli_servo_averaging.save();
|
||||
|
||||
// return swash plate movements to attitude controller
|
||||
heli_manual_override = false;
|
||||
g.heli_servo_manual = false;
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
@ -178,6 +178,7 @@ static void init_ardupilot()
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
g.heli_servo_manual = false;
|
||||
heli_init_swash(); // heli initialisation
|
||||
#endif
|
||||
|
||||
|
@ -183,7 +183,7 @@ static void update_crosstrack(void)
|
||||
|
||||
static void reset_crosstrack()
|
||||
{
|
||||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
||||
crosstrack_bearing = get_bearing(&prev_WP, &next_WP); // Used for track following
|
||||
}
|
||||
|
||||
static long get_distance(struct Location *loc1, struct Location *loc2)
|
||||
|
@ -2,6 +2,7 @@
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Management;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
@ -54,6 +55,26 @@ namespace ArdupilotMega
|
||||
|
||||
System.Threading.Thread.Sleep(500);
|
||||
|
||||
//HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
|
||||
if (!MainV2.MAC)
|
||||
{
|
||||
ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
|
||||
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
|
||||
foreach (ManagementObject obj2 in searcher.Get())
|
||||
{
|
||||
Console.WriteLine("Dependant : " + obj2["Dependent"]);
|
||||
|
||||
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
|
||||
{
|
||||
return "2560-2";
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
int fixme;
|
||||
}
|
||||
|
||||
serialPort.DtrEnable = true;
|
||||
serialPort.BaudRate = 115200;
|
||||
serialPort.Open();
|
||||
@ -92,7 +113,7 @@ namespace ArdupilotMega
|
||||
port = new ArduinoSTK();
|
||||
port.BaudRate = 57600;
|
||||
}
|
||||
else if (version == "2560")
|
||||
else if (version == "2560" || version == "2560-2")
|
||||
{
|
||||
port = new ArduinoSTKv2();
|
||||
port.BaudRate = 115200;
|
||||
|
@ -166,6 +166,7 @@
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\x86\System.Data.SQLite.DLL</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="System.Drawing" />
|
||||
<Reference Include="System.Management" />
|
||||
<Reference Include="System.Speech">
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
|
@ -508,7 +508,7 @@ namespace ArdupilotMega.GCSViews
|
||||
ofd.AddExtension = true;
|
||||
ofd.DefaultExt = ".param";
|
||||
ofd.RestoreDirectory = true;
|
||||
ofd.Filter = "Param List|*.param";
|
||||
ofd.Filter = "Param List|*.param;*.parm";
|
||||
DialogResult dr = ofd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
@ -562,7 +562,7 @@ namespace ArdupilotMega.GCSViews
|
||||
sfd.AddExtension = true;
|
||||
sfd.DefaultExt = ".param";
|
||||
sfd.RestoreDirectory = true;
|
||||
sfd.Filter = "Param List|*.param";
|
||||
sfd.Filter = "Param List|*.param;*.parm";
|
||||
DialogResult dr = sfd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
@ -1005,7 +1005,7 @@ namespace ArdupilotMega.GCSViews
|
||||
ofd.AddExtension = true;
|
||||
ofd.DefaultExt = ".param";
|
||||
ofd.RestoreDirectory = true;
|
||||
ofd.Filter = "Param List|*.param";
|
||||
ofd.Filter = "Param List|*.param;*.parm";
|
||||
DialogResult dr = ofd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
|
@ -514,10 +514,15 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
baseurl = temp.url2560.ToString();
|
||||
}
|
||||
else
|
||||
else if (board == "1280")
|
||||
{
|
||||
baseurl = temp.url.ToString();
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Invalid Board Type");
|
||||
return;
|
||||
}
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(baseurl);
|
||||
|
@ -112,7 +112,7 @@ namespace ArdupilotMega.HIL
|
||||
double pitch_accel = (m[2] - m[3]) * 5000.0;
|
||||
double yaw_accel = -((m[2] + m[3]) - (m[0] + m[1])) * 400.0;
|
||||
|
||||
// Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
|
||||
//Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
|
||||
|
||||
//# update rotational rates
|
||||
roll_rate += roll_accel * delta_time.TotalSeconds;
|
||||
|
@ -348,16 +348,22 @@ namespace ArdupilotMega
|
||||
|
||||
public void sendPacket(object indata)
|
||||
{
|
||||
bool run = false;
|
||||
byte a = 0;
|
||||
foreach (Type ty in mavstructs)
|
||||
{
|
||||
if (ty == indata.GetType())
|
||||
{
|
||||
run = true;
|
||||
generatePacket(a, indata);
|
||||
return;
|
||||
}
|
||||
a++;
|
||||
}
|
||||
if (!run)
|
||||
{
|
||||
Console.WriteLine("Mavlink : NOT VALID PACKET sendPacket() "+indata.GetType().ToString());
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
|
@ -305,20 +305,6 @@ namespace ArdupilotMega
|
||||
|
||||
};
|
||||
|
||||
public const byte MAVLINK_MSG_ID_ATTITUDE_NEW = 30;
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||
public struct __mavlink_attitude_new_t
|
||||
{
|
||||
public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
|
||||
public float roll; /// Roll angle (rad)
|
||||
public float pitch; /// Pitch angle (rad)
|
||||
public float yaw; /// Yaw angle (rad)
|
||||
public float rollspeed; /// Roll angular speed (rad/s)
|
||||
public float pitchspeed; /// Pitch angular speed (rad/s)
|
||||
public float yawspeed; /// Yaw angular speed (rad/s)
|
||||
|
||||
};
|
||||
|
||||
public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||
public struct __mavlink_auth_key_t
|
||||
@ -1486,7 +1472,7 @@ namespace ArdupilotMega
|
||||
MAV_FRAME_LOCAL_ENU = 4
|
||||
};
|
||||
|
||||
Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_new_t ) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_waypoint_set_global_reference_t ) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,typeof( __mavlink_attitude_controller_output_t ) ,typeof( __mavlink_position_controller_output_t ) ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_request_dynamic_gyro_calibration_t ) ,typeof( __mavlink_request_static_calibration_t ) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
|
||||
Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t ) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_waypoint_set_global_reference_t ) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,typeof( __mavlink_attitude_controller_output_t ) ,typeof( __mavlink_position_controller_output_t ) ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_request_dynamic_gyro_calibration_t ) ,typeof( __mavlink_request_static_calibration_t ) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
|
||||
|
||||
}
|
||||
#endif
|
||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.0.90")]
|
||||
[assembly: AssemblyFileVersion("1.0.91")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
@ -442,6 +442,12 @@ namespace ArdupilotMega.Setup
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
HS1_REV.Checked = MainV2.comPort.param["HS1_REV"].ToString() == "-1";
|
||||
HS2_REV.Checked = MainV2.comPort.param["HS2_REV"].ToString() == "-1";
|
||||
HS3_REV.Checked = MainV2.comPort.param["HS3_REV"].ToString() == "-1";
|
||||
HS4_REV.Checked = MainV2.comPort.param["HS4_REV"].ToString() == "-1";
|
||||
|
||||
}
|
||||
catch { }
|
||||
startup = false;
|
||||
@ -910,28 +916,28 @@ namespace ArdupilotMega.Setup
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f);
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS2_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f);
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS3_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f);
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS4_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : -1.0f);
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS1_TRIM_Scroll(object sender, EventArgs e)
|
||||
@ -1016,6 +1022,20 @@ namespace ArdupilotMega.Setup
|
||||
{
|
||||
try
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
return;
|
||||
}
|
||||
}
|
||||
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
||||
|
||||
MainV2.comPort.setParam("COL_MIN_", HS3.minline);
|
||||
MainV2.comPort.setParam("COL_MAX_", HS3.maxline);
|
||||
|
||||
|
@ -3008,13 +3008,13 @@ will work with hexa's etc</value>
|
||||
<value>430, 307</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>90, 23</value>
|
||||
<value>90, 41</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>111</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.Text" xml:space="preserve">
|
||||
<value>Save Travel</value>
|
||||
<value>Manual Travel / Save Travel</value>
|
||||
</data>
|
||||
<data name=">>BUT_saveheliconfig.Name" xml:space="preserve">
|
||||
<value>BUT_saveheliconfig</value>
|
||||
|
@ -11,7 +11,7 @@
|
||||
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
||||
</dsig:Transforms>
|
||||
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
||||
<dsig:DigestValue>asA4p3xM8idcyyuyecIXR3bVsug=</dsig:DigestValue>
|
||||
<dsig:DigestValue>dszV+o57dCwksPcpzEBhuhMS3T8=</dsig:DigestValue>
|
||||
</hash>
|
||||
</dependentAssembly>
|
||||
</dependency>
|
||||
|
@ -3008,13 +3008,13 @@ will work with hexa's etc</value>
|
||||
<value>430, 307</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>90, 23</value>
|
||||
<value>90, 41</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>111</value>
|
||||
</data>
|
||||
<data name="BUT_saveheliconfig.Text" xml:space="preserve">
|
||||
<value>Save Travel</value>
|
||||
<value>Manual Travel / Save Travel</value>
|
||||
</data>
|
||||
<data name=">>BUT_saveheliconfig.Name" xml:space="preserve">
|
||||
<value>BUT_saveheliconfig</value>
|
||||
|
@ -275,8 +275,12 @@ def setup_rc(mavproxy):
|
||||
mavproxy.send('rc 3 1000\n')
|
||||
|
||||
|
||||
def fly_ArduCopter():
|
||||
'''fly ArduCopter in SIL'''
|
||||
def fly_ArduCopter(viewerip=None):
|
||||
'''fly ArduCopter in SIL
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
mavproxy packets too for local viewing of the flight in real time
|
||||
'''
|
||||
global expect_list, homeloc
|
||||
|
||||
sil = util.start_SIL('ArduCopter', wipe=True)
|
||||
@ -295,12 +299,13 @@ def fly_ArduCopter():
|
||||
mavproxy.expect('Loaded [0-9]+ parameters')
|
||||
|
||||
# reboot with new parameters
|
||||
print("CLOSING")
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
print("CLOSED THEM")
|
||||
sil = util.start_SIL('ArduCopter')
|
||||
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --out=192.168.2.15:14550 --quadcopter --streamrate=1')
|
||||
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
|
||||
mavproxy.expect('Logging to (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
print("LOGFILE %s" % logfile)
|
||||
@ -317,8 +322,10 @@ def fly_ArduCopter():
|
||||
util.expect_setup_callback(mavproxy, expect_callback)
|
||||
|
||||
# start hil_quad.py
|
||||
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --fgrate=200 --home=%s' % HOME_LOCATION,
|
||||
logfile=sys.stdout, timeout=10)
|
||||
cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%s' % HOME_LOCATION
|
||||
if viewerip:
|
||||
cmd += ' --fgout=192.168.2.15:9123'
|
||||
hquad = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
|
||||
util.pexpect_autoclose(hquad)
|
||||
hquad.expect('Starting at')
|
||||
|
||||
|
@ -295,11 +295,15 @@ void FastSerial::flush(void)
|
||||
void FastSerial::write(uint8_t c)
|
||||
{
|
||||
struct tcp_state *s = &tcp_state[_u2x];
|
||||
int flags = MSG_NOSIGNAL;
|
||||
check_connection(s);
|
||||
if (!s->connected) {
|
||||
return;
|
||||
}
|
||||
send(s->fd, &c, 1, MSG_DONTWAIT | MSG_NOSIGNAL);
|
||||
if (!desktop_state.slider) {
|
||||
flags |= MSG_DONTWAIT;
|
||||
}
|
||||
send(s->fd, &c, 1, flags);
|
||||
}
|
||||
|
||||
// Buffer management ///////////////////////////////////////////////////////////
|
||||
|
Loading…
Reference in New Issue
Block a user