Added connection delay to account for Arduino auto-reset
Tweaked values for 320 kV motor
This commit is contained in:
parent
bf94dc733c
commit
3f68e6d8d9
|
@ -176,4 +176,11 @@ object MainForm: TMainForm
|
||||||
Left = 424
|
Left = 424
|
||||||
Top = 80
|
Top = 80
|
||||||
end
|
end
|
||||||
|
object ConnectWaitTimer: TTimer
|
||||||
|
Enabled = False
|
||||||
|
Interval = 100
|
||||||
|
OnTimer = ConnectWaitTimerTimer
|
||||||
|
Left = 504
|
||||||
|
Top = 24
|
||||||
|
end
|
||||||
end
|
end
|
||||||
|
|
|
@ -34,6 +34,7 @@ type
|
||||||
SimulatorPanel: TPanel;
|
SimulatorPanel: TPanel;
|
||||||
SimulatorSelectionPanel: TPanel;
|
SimulatorSelectionPanel: TPanel;
|
||||||
SimulatorLockButton: TSpeedButton;
|
SimulatorLockButton: TSpeedButton;
|
||||||
|
ConnectWaitTimer: TTimer;
|
||||||
|
|
||||||
procedure FormCreate(Sender: TObject);
|
procedure FormCreate(Sender: TObject);
|
||||||
procedure PortComboBoxClick(Sender: TObject);
|
procedure PortComboBoxClick(Sender: TObject);
|
||||||
|
@ -43,6 +44,7 @@ type
|
||||||
procedure CalibrationButtonClick(Sender: TObject);
|
procedure CalibrationButtonClick(Sender: TObject);
|
||||||
procedure SimulatorComboBoxClick(Sender: TObject);
|
procedure SimulatorComboBoxClick(Sender: TObject);
|
||||||
procedure SimulatorLockButtonClick(Sender: TObject);
|
procedure SimulatorLockButtonClick(Sender: TObject);
|
||||||
|
procedure ConnectWaitTimerTimer(Sender: TObject);
|
||||||
private
|
private
|
||||||
FComPort: TComPort;
|
FComPort: TComPort;
|
||||||
FReceived: string;
|
FReceived: string;
|
||||||
|
@ -63,6 +65,7 @@ type
|
||||||
procedure StartCommand;
|
procedure StartCommand;
|
||||||
procedure EndCommand;
|
procedure EndCommand;
|
||||||
procedure OnReceiveChar(Sender: TObject; Count: Integer);
|
procedure OnReceiveChar(Sender: TObject; Count: Integer);
|
||||||
|
procedure OnAfterClose(Sender: TObject);
|
||||||
|
|
||||||
function ValidFanIndex(AFan: Byte): Boolean; inline;
|
function ValidFanIndex(AFan: Byte): Boolean; inline;
|
||||||
|
|
||||||
|
@ -368,6 +371,7 @@ begin
|
||||||
FComPort := TComPort.Create(Self);
|
FComPort := TComPort.Create(Self);
|
||||||
FComPort.BaudRate := br19200;
|
FComPort.BaudRate := br19200;
|
||||||
FComPort.OnRxChar := OnReceiveChar;
|
FComPort.OnRxChar := OnReceiveChar;
|
||||||
|
FComPort.OnAfterClose := OnAfterClose;
|
||||||
end;
|
end;
|
||||||
|
|
||||||
newPort := PortComboBox.Items[PortComboBox.ItemIndex];
|
newPort := PortComboBox.Items[PortComboBox.ItemIndex];
|
||||||
|
@ -378,26 +382,9 @@ begin
|
||||||
try
|
try
|
||||||
ComPort.Open;
|
ComPort.Open;
|
||||||
|
|
||||||
SendCommand('>Info',
|
{ The Arduino resets when a serial connection is made, wait for a bit
|
||||||
procedure(Response: string)
|
before sending the first Info command }
|
||||||
begin
|
ConnectWaitTimer.Enabled := True;
|
||||||
if AnsiStartsText('<Info:', Response) then
|
|
||||||
begin
|
|
||||||
PortStatusLabel.Caption := 'Connected';
|
|
||||||
InitDevice(Copy(Response, 7, MaxInt));
|
|
||||||
FReady := True;
|
|
||||||
end else
|
|
||||||
begin
|
|
||||||
PortStatusLabel.Caption := 'Invalid response';
|
|
||||||
ConnectTimer.Enabled := True;
|
|
||||||
end;
|
|
||||||
end,
|
|
||||||
|
|
||||||
procedure
|
|
||||||
begin
|
|
||||||
PortStatusLabel.Caption := 'No response';
|
|
||||||
ConnectTimer.Enabled := True;
|
|
||||||
end);
|
|
||||||
except
|
except
|
||||||
on E:Exception do
|
on E:Exception do
|
||||||
begin
|
begin
|
||||||
|
@ -408,6 +395,34 @@ begin
|
||||||
end;
|
end;
|
||||||
|
|
||||||
|
|
||||||
|
procedure TMainForm.ConnectWaitTimerTimer(Sender: TObject);
|
||||||
|
begin
|
||||||
|
ConnectWaitTimer.Enabled := False;
|
||||||
|
|
||||||
|
SendCommand(#10'>Info',
|
||||||
|
procedure(Response: string)
|
||||||
|
begin
|
||||||
|
if AnsiStartsText('<Info:', Response) then
|
||||||
|
begin
|
||||||
|
PortStatusLabel.Caption := 'Connected';
|
||||||
|
InitDevice(Copy(Response, 7, MaxInt));
|
||||||
|
FReady := True;
|
||||||
|
end else
|
||||||
|
begin
|
||||||
|
PortStatusLabel.Caption := 'Invalid response';
|
||||||
|
ConnectTimer.Enabled := True;
|
||||||
|
end;
|
||||||
|
end,
|
||||||
|
|
||||||
|
procedure
|
||||||
|
begin
|
||||||
|
PortStatusLabel.Caption := 'No response';
|
||||||
|
ConnectTimer.Enabled := True;
|
||||||
|
end);
|
||||||
|
end;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
procedure TMainForm.OnReceiveChar(Sender: TObject; Count: Integer);
|
procedure TMainForm.OnReceiveChar(Sender: TObject; Count: Integer);
|
||||||
var
|
var
|
||||||
data: string;
|
data: string;
|
||||||
|
@ -430,6 +445,13 @@ begin
|
||||||
end;
|
end;
|
||||||
|
|
||||||
|
|
||||||
|
procedure TMainForm.OnAfterClose(Sender: TObject);
|
||||||
|
begin
|
||||||
|
PortStatusLabel.Caption := 'Not connected';
|
||||||
|
ConnectTimer.Enabled := True;
|
||||||
|
end;
|
||||||
|
|
||||||
|
|
||||||
function TMainForm.ValidFanIndex(AFan: Byte): Boolean;
|
function TMainForm.ValidFanIndex(AFan: Byte): Boolean;
|
||||||
begin
|
begin
|
||||||
Result := AFan < Length(FFanValues);
|
Result := AFan < Length(FFanValues);
|
||||||
|
|
|
@ -83,7 +83,7 @@ const byte FanPin[FanCount] =
|
||||||
|
|
||||||
// The minimum value at which the fan still spins reliably. Anything below
|
// The minimum value at which the fan still spins reliably. Anything below
|
||||||
// will be considered as 0.
|
// will be considered as 0.
|
||||||
#define MinimumValue 70
|
#define MinimumValue 30
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -105,7 +105,7 @@ const byte FanPin[FanCount] =
|
||||||
|
|
||||||
// The pulse width when the input value is 255, in microseconds.
|
// The pulse width when the input value is 255, in microseconds.
|
||||||
// Use this to limit the maximum "throttle" to the ESC.
|
// Use this to limit the maximum "throttle" to the ESC.
|
||||||
#define ServoMaxValue (ServoMinPulseWidth + (ServoPulseRange / 4))
|
#define ServoMaxValue ServoMinPulseWidth + ServoPulseRange
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue