Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
P
proview
Project overview
Project overview
Details
Activity
Releases
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Analytics
Analytics
CI / CD
Repository
Value Stream
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Esteban Blanc
proview
Commits
51d8a9e3
Commit
51d8a9e3
authored
Mar 04, 2012
by
claes
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
IO arduino fix
parent
826ee2c5
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
83 additions
and
423 deletions
+83
-423
otherio/exp/rt/src/pwr_arduino_uno.ino
otherio/exp/rt/src/pwr_arduino_uno.ino
+1
-1
otherio/exp/rt/src/pwr_arduino_uno.pde
otherio/exp/rt/src/pwr_arduino_uno.pde
+0
-397
otherio/lib/rt/src/rt_io_m_arduino_uno.c
otherio/lib/rt/src/rt_io_m_arduino_uno.c
+74
-24
otherio/wbl/mcomp/src/otherio.wb_load
otherio/wbl/mcomp/src/otherio.wb_load
+8
-1
No files found.
otherio/exp/rt/src/pwr_arduino_uno.ino
View file @
51d8a9e3
...
@@ -20,7 +20,7 @@
...
@@ -20,7 +20,7 @@
// Sketch for Arduino USB board to communicate with Proview I/O
// Sketch for Arduino USB board to communicate with Proview I/O
// object OtherIO:Arduino_Uno.
// object OtherIO:Arduino_Uno.
//
//
byte
firmware
[
20
]
=
"Proview
2012-02-29
"
;
byte
firmware
[
20
]
=
"Proview
V2.0.0-1
"
;
byte
version_major
=
2
;
byte
version_major
=
2
;
byte
version_minor
=
0
;
byte
version_minor
=
0
;
byte
msg
=
0
;
byte
msg
=
0
;
...
...
otherio/exp/rt/src/pwr_arduino_uno.pde
deleted
100644 → 0
View file @
826ee2c5
//
// Proview
// Copyright (C) 2010 SSAB Oxelösund AB.
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License as
// published by the Free Software Foundation, either version 2 of
// the License, or (at your option) any later version.
//
// This program is distributed in the hope that it will be useful
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with the program, if not, write to the Free Software
// Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
//
// Description:
// Sketch for Arduino USB board to communicate with Proview I/O
// object OtherIO:Arduino_Uno.
//
byte
msg
=
0
;
byte
sts
;
int
val
=
0
;
byte
amsg
[
50
];
byte
smsg
[
10
];
byte
diSize
=
0
;
byte
doSize
=
0
;
byte
aiSize
=
0
;
byte
aoSize
=
0
;
byte
diMask
[
10
];
byte
doMask
[
10
];
byte
aiMask
[
4
];
byte
aoMask
[
4
];
int
watchdogTime
=
5000
;
int
status
;
int
i
;
int
j
;
int
aiList
[
32
];
int
aiCnt
;
int
aoList
[
32
];
int
aoCnt
;
byte
msgType
;
byte
msgId
;
byte
msgSize
;
byte
msgData
[
100
];
byte
rmsg
[
40
];
int
sizeErrorCnt
=
0
;
int
noMessageCnt
=
0
;
const
int
delayTime
=
1
;
const
int
debug
=
0
;
const
int
MSG_TYPE_DOWRITE
=
1
;
const
int
MSG_TYPE_DIREAD
=
2
;
const
int
MSG_TYPE_AIREAD
=
3
;
const
int
MSG_TYPE_AOWRITE
=
4
;
const
int
MSG_TYPE_CONFIGURE
=
5
;
const
int
MSG_TYPE_STATUS
=
6
;
const
int
MSG_TYPE_DEBUG
=
7
;
const
int
MSG_TYPE_WRITEALL
=
8
;
const
int
MSG_TYPE_READALL
=
9
;
const
int
ARD__SUCCESS
=
1
;
const
int
ARD__DICONFIG
=
2
;
const
int
ARD__DOCONFIG
=
4
;
const
int
ARD__AICONFIG
=
6
;
const
int
ARD__AOCONFIG
=
8
;
const
int
ARD__COMMERROR
=
10
;
const
int
ARD__MSGSIZE
=
12
;
const
int
ARD__NOMSG
=
14
;
void
sendDebug
(
byte
sts
)
{
rmsg
[
0
]
=
4
;
rmsg
[
1
]
=
0
;
rmsg
[
2
]
=
MSG_TYPE_DEBUG
;
rmsg
[
3
]
=
sts
;
Serial
.
write
(
rmsg
,
rmsg
[
0
]);
}
//
// Reset all outputs when communication communication is down
//
void
resetOutput
()
{
for
(
i
=
0
;
i
<
doSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
doMask
[
i
])
!=
0
)
digitalWrite
(
i
*
8
+
j
,
LOW
);
}
}
for
(
i
=
0
;
i
<
aoCnt
;
i
++
)
analogWrite
(
aoList
[
i
],
0
);
}
//
// Read a message from the serial port
//
int
serialRead
()
{
int
num
;
num
=
Serial
.
available
();
if
(
num
==
0
)
return
ARD__NOMSG
;
msgSize
=
Serial
.
peek
();
if
(
num
<
msgSize
)
return
ARD__MSGSIZE
;
msgSize
=
Serial
.
read
();
msgId
=
Serial
.
read
();
msgType
=
Serial
.
read
();
msgSize
-=
3
;
for
(
int
i
=
0
;
i
<
msgSize
;
i
++
)
msgData
[
i
]
=
Serial
.
read
();
if
(
debug
)
{
rmsg
[
0
]
=
msgSize
+
3
;
rmsg
[
1
]
=
msgId
;
rmsg
[
2
]
=
MSG_TYPE_DEBUG
;
for
(
int
j
=
0
;
j
<
msgSize
;
j
++
)
rmsg
[
j
+
3
]
=
msgData
[
j
];
Serial
.
write
(
rmsg
,
msgSize
+
3
);
}
return
ARD__SUCCESS
;
}
void
setup
()
{
// Start serial port at the configured baud rate
Serial
.
begin
(
9600
);
Serial
.
flush
();
}
void
loop
()
{
status
=
serialRead
();
if
(
status
==
ARD__NOMSG
)
{
if
(
watchdogTime
!=
0
)
{
// Increment watchdog counter
noMessageCnt
++
;
if
(
noMessageCnt
*
delayTime
>
watchdogTime
)
resetOutput
();
}
}
else
if
(
status
==
ARD__MSGSIZE
)
{
sizeErrorCnt
++
;
if
(
sizeErrorCnt
>
50
)
{
Serial
.
flush
();
sizeErrorCnt
=
0
;
}
}
else
if
(
(
status
&
1
)
!=
0
)
{
// A message is received
sizeErrorCnt
=
0
;
noMessageCnt
=
0
;
if
(
msgType
==
MSG_TYPE_DOWRITE
)
{
// Write digital outputs
if
(
msgSize
==
doSize
)
{
for
(
i
=
0
;
i
<
doSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
doMask
[
i
])
!=
0
)
{
if
(
((
1
<<
j
)
&
msgData
[
i
])
!=
0
)
digitalWrite
(
i
*
8
+
j
,
HIGH
);
else
digitalWrite
(
i
*
8
+
j
,
LOW
);
}
}
}
sts
=
ARD__SUCCESS
;
}
else
{
sts
=
ARD__COMMERROR
;
}
}
else
if
(
msgType
==
MSG_TYPE_AOWRITE
)
{
// Write analog outputs
if
(
msgSize
==
aoCnt
)
{
for
(
i
=
0
;
i
<
aoCnt
;
i
++
)
analogWrite
(
aoList
[
i
],
msgData
[
i
]);
sts
=
ARD__SUCCESS
;
}
else
{
sts
=
ARD__COMMERROR
;
}
}
else
if
(
msgType
==
MSG_TYPE_WRITEALL
)
{
// Write digital outputs
if
(
msgSize
==
doSize
+
aoCnt
)
{
for
(
i
=
0
;
i
<
doSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
doMask
[
i
])
!=
0
)
{
if
(
((
1
<<
j
)
&
msgData
[
i
])
!=
0
)
digitalWrite
(
i
*
8
+
j
,
HIGH
);
else
digitalWrite
(
i
*
8
+
j
,
LOW
);
}
}
}
for
(
i
=
0
;
i
<
aoCnt
;
i
++
)
analogWrite
(
aoList
[
i
],
msgData
[
doSize
+
i
]);
sts
=
ARD__SUCCESS
;
}
else
{
sts
=
ARD__COMMERROR
;
}
}
else
if
(
msgType
==
MSG_TYPE_DIREAD
)
{
// Read Digital inputs
smsg
[
0
]
=
diSize
+
3
;
smsg
[
1
]
=
msgId
;
smsg
[
2
]
=
MSG_TYPE_DIREAD
;
for
(
i
=
0
;
i
<
diSize
;
i
++
)
{
smsg
[
i
+
3
]
=
0
;
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
diMask
[
i
])
!=
0
)
{
val
=
digitalRead
(
i
*
8
+
j
);
if
(
val
==
HIGH
)
smsg
[
i
+
3
]
|=
1
<<
j
;
}
}
}
Serial
.
write
(
smsg
,
smsg
[
0
]);
}
else
if
(
msgType
==
MSG_TYPE_AIREAD
)
{
// Read analog inputs
amsg
[
0
]
=
aiCnt
*
2
+
3
;
amsg
[
1
]
=
msgId
;
amsg
[
2
]
=
MSG_TYPE_AIREAD
;
for
(
i
=
0
;
i
<
aiCnt
;
i
++
)
{
val
=
analogRead
(
aiList
[
i
]);
amsg
[
i
*
2
+
3
]
=
val
/
256
;
amsg
[
i
*
2
+
1
+
3
]
=
val
%
256
;
}
Serial
.
write
(
amsg
,
amsg
[
0
]);
}
else
if
(
msgType
==
MSG_TYPE_READALL
)
{
// Read Digital inputs
amsg
[
0
]
=
diSize
+
aiCnt
*
2
+
3
;
amsg
[
1
]
=
msgId
;
amsg
[
2
]
=
MSG_TYPE_READALL
;
for
(
i
=
0
;
i
<
diSize
;
i
++
)
{
amsg
[
i
+
3
]
=
0
;
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
diMask
[
i
])
!=
0
)
{
val
=
digitalRead
(
i
*
8
+
j
);
if
(
val
==
HIGH
)
amsg
[
i
+
3
]
|=
1
<<
j
;
}
}
}
for
(
i
=
0
;
i
<
aiCnt
;
i
++
)
{
val
=
analogRead
(
aiList
[
i
]);
amsg
[
diSize
+
i
*
2
+
3
]
=
val
/
256
;
amsg
[
diSize
+
i
*
2
+
1
+
3
]
=
val
%
256
;
}
Serial
.
write
(
amsg
,
amsg
[
0
]);
}
else
if
(
msgType
==
MSG_TYPE_CONFIGURE
)
{
// Configure message
int
offs
=
0
;
sts
=
ARD__SUCCESS
;
if
(
debug
)
{
smsg
[
0
]
=
msgSize
+
3
;
smsg
[
1
]
=
msgId
;
smsg
[
2
]
=
MSG_TYPE_DEBUG
;
for
(
int
j
=
0
;
j
<
msgSize
;
j
++
)
smsg
[
j
+
3
]
=
msgData
[
j
];
Serial
.
write
(
smsg
,
smsg
[
0
]);
}
watchdogTime
=
msgData
[
offs
++
]
*
100
;
diSize
=
msgData
[
offs
++
];
if
(
diSize
>
10
)
{
diSize
=
10
;
sts
=
ARD__DICONFIG
;
}
if
(
sts
&
1
!=
0
)
{
for
(
i
=
0
;
i
<
diSize
;
i
++
)
diMask
[
i
]
=
msgData
[
offs
++
];
}
if
(
sts
&
1
!=
0
)
{
doSize
=
msgData
[
offs
++
];
if
(
doSize
>
10
)
{
doSize
=
10
;
sts
=
ARD__DOCONFIG
;
}
}
if
(
sts
&
1
!=
0
)
{
for
(
i
=
0
;
i
<
doSize
;
i
++
)
doMask
[
i
]
=
msgData
[
offs
++
];
}
if
(
sts
&
1
!=
0
)
{
aiSize
=
msgData
[
offs
++
];
if
(
aiSize
>
4
)
{
aiSize
=
4
;
sts
=
ARD__AICONFIG
;
}
}
if
(
sts
&
1
!=
0
)
{
for
(
i
=
0
;
i
<
aiSize
;
i
++
)
aiMask
[
i
]
=
msgData
[
offs
++
];
}
if
(
sts
&
1
!=
0
)
{
aoSize
=
msgData
[
offs
++
];
if
(
aoSize
>
4
)
{
aoSize
=
4
;
sts
=
ARD__AOCONFIG
;
}
}
if
(
sts
&
1
!=
0
)
{
for
(
i
=
0
;
i
<
aoSize
;
i
++
)
aoMask
[
i
]
=
msgData
[
offs
++
];
}
if
(
sts
&
1
!=
0
)
{
// Set Di pinmode
for
(
i
=
0
;
i
<
diSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
diMask
[
i
])
!=
0
)
pinMode
(
i
*
8
+
j
,
INPUT
);
}
}
// Set Do pinmode
for
(
i
=
0
;
i
<
doSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
doMask
[
i
])
!=
0
)
pinMode
(
i
*
8
+
j
,
OUTPUT
);
}
}
// Create list of configured Ai
aiCnt
=
0
;
for
(
i
=
0
;
i
<
aiSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
aiMask
[
i
])
!=
0
)
{
aiList
[
aiCnt
]
=
i
*
8
+
j
;
aiCnt
++
;
}
}
}
// Create list of configured Ao
aoCnt
=
0
;
for
(
i
=
0
;
i
<
aoSize
;
i
++
)
{
for
(
j
=
0
;
j
<
8
;
j
++
)
{
if
(
((
1
<<
j
)
&
aoMask
[
i
])
!=
0
)
{
aoList
[
aoCnt
]
=
i
*
8
+
j
;
aoCnt
++
;
}
}
}
}
// Send configuration status
smsg
[
0
]
=
4
;
smsg
[
1
]
=
msgId
;
smsg
[
2
]
=
MSG_TYPE_STATUS
;
smsg
[
3
]
=
sts
;
Serial
.
write
(
smsg
,
4
);
}
}
else
{
// Return error status
smsg
[
0
]
=
4
;
smsg
[
1
]
=
msgId
;
smsg
[
2
]
=
MSG_TYPE_STATUS
;
smsg
[
3
]
=
status
;
Serial
.
write
(
smsg
,
4
);
}
delay
(
delayTime
);
}
otherio/lib/rt/src/rt_io_m_arduino_uno.c
View file @
51d8a9e3
...
@@ -98,6 +98,8 @@ typedef struct {
...
@@ -98,6 +98,8 @@ typedef struct {
int
WriteId
;
int
WriteId
;
int
AiIntervalCnt
;
int
AiIntervalCnt
;
int
AoIntervalCnt
;
int
AoIntervalCnt
;
int
Reopendev
;
int
ReopendevCnt
;
int
Reconnect
;
int
Reconnect
;
int
ReconnectCnt
;
int
ReconnectCnt
;
int
VersionMajor
;
int
VersionMajor
;
...
@@ -144,6 +146,11 @@ static void add_checksum( void *buf);
...
@@ -144,6 +146,11 @@ static void add_checksum( void *buf);
static
int
check_checksum
(
void
*
buf
);
static
int
check_checksum
(
void
*
buf
);
static
int
receive
(
int
fd
,
int
id
,
ard_sMsg
*
rmsg
,
int
size
,
float
tmo
,
pwr_sClass_Arduino_Uno
*
op
);
static
int
receive
(
int
fd
,
int
id
,
ard_sMsg
*
rmsg
,
int
size
,
float
tmo
,
pwr_sClass_Arduino_Uno
*
op
);
static
int
close_device
(
io_sLocal
*
local
)
{
close
(
local
->
fd
);
return
IO__SUCCESS
;
}
static
int
open_device
(
io_sLocal
*
local
,
pwr_sClass_Arduino_Uno
*
op
,
io_sCard
*
cp
)
static
int
open_device
(
io_sLocal
*
local
,
pwr_sClass_Arduino_Uno
*
op
,
io_sCard
*
cp
)
{
{
...
@@ -210,6 +217,8 @@ static int open_device( io_sLocal *local, pwr_sClass_Arduino_Uno *op, io_sCard *
...
@@ -210,6 +217,8 @@ static int open_device( io_sLocal *local, pwr_sClass_Arduino_Uno *op, io_sCard *
tcflush
(
local
->
fd
,
TCIOFLUSH
);
tcflush
(
local
->
fd
,
TCIOFLUSH
);
sleep
(
5
);
return
IO__SUCCESS
;
return
IO__SUCCESS
;
}
}
...
@@ -263,8 +272,6 @@ static int send_configuration( io_sLocal *local, pwr_sClass_Arduino_Uno *op, io_
...
@@ -263,8 +272,6 @@ static int send_configuration( io_sLocal *local, pwr_sClass_Arduino_Uno *op, io_
printf
(
"%u "
,
msg
.
data
[
i
]);
printf
(
"%u "
,
msg
.
data
[
i
]);
printf
(
"
\n
"
);
printf
(
"
\n
"
);
sleep
(
5
);
if
(
op
->
Options
&
pwr_mArduino_OptionsMask_Checksum
)
if
(
op
->
Options
&
pwr_mArduino_OptionsMask_Checksum
)
add_checksum
(
&
msg
);
add_checksum
(
&
msg
);
...
@@ -310,8 +317,8 @@ static int send_connect_request( io_sLocal *local, pwr_sClass_Arduino_Uno *op, i
...
@@ -310,8 +317,8 @@ static int send_connect_request( io_sLocal *local, pwr_sClass_Arduino_Uno *op, i
op
->
Status
=
rmsg
.
data
[
0
];
op
->
Status
=
rmsg
.
data
[
0
];
local
->
VersionMajor
=
rmsg
.
data
[
1
];
local
->
VersionMajor
=
rmsg
.
data
[
1
];
local
->
VersionMinor
=
rmsg
.
data
[
2
];
local
->
VersionMinor
=
rmsg
.
data
[
2
];
snprintf
(
op
->
FirmwareVersion
,
sizeof
(
op
->
FirmwareVersion
),
"
V%d.%d
%s"
,
snprintf
(
op
->
FirmwareVersion
,
sizeof
(
op
->
FirmwareVersion
),
"%s"
,
local
->
VersionMajor
,
local
->
VersionMinor
,
(
char
*
)
&
rmsg
.
data
[
3
]);
(
char
*
)
&
rmsg
.
data
[
3
]);
}
}
else
{
else
{
return
IO__INITFAIL
;
return
IO__INITFAIL
;
...
@@ -320,6 +327,24 @@ static int send_connect_request( io_sLocal *local, pwr_sClass_Arduino_Uno *op, i
...
@@ -320,6 +327,24 @@ static int send_connect_request( io_sLocal *local, pwr_sClass_Arduino_Uno *op, i
return
IO__SUCCESS
;
return
IO__SUCCESS
;
}
}
static
int
open_and_connect
(
io_sLocal
*
local
,
pwr_sClass_Arduino_Uno
*
op
,
io_sCard
*
cp
)
{
int
sts
;
sts
=
open_device
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
if
(
op
->
Options
&
pwr_mArduino_OptionsMask_ConnectionRequest
)
{
sts
=
send_connect_request
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
}
sts
=
send_configuration
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
return
IO__SUCCESS
;
}
static
void
add_checksum
(
void
*
buf
)
static
void
add_checksum
(
void
*
buf
)
{
{
int
i
;
int
i
;
...
@@ -564,15 +589,7 @@ static pwr_tStatus IoCardInit( io_tCtx ctx,
...
@@ -564,15 +589,7 @@ static pwr_tStatus IoCardInit( io_tCtx ctx,
}
}
}
}
sts
=
open_device
(
local
,
op
,
cp
);
sts
=
open_and_connect
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
if
(
op
->
Options
&
pwr_mArduino_OptionsMask_ConnectionRequest
)
{
sts
=
send_connect_request
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
}
sts
=
send_configuration
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
return
sts
;
if
(
EVEN
(
sts
))
return
sts
;
errh_Info
(
"Init of Arduino card '%s'"
,
cp
->
Name
);
errh_Info
(
"Init of Arduino card '%s'"
,
cp
->
Name
);
...
@@ -587,7 +604,7 @@ static pwr_tStatus IoCardClose( io_tCtx ctx,
...
@@ -587,7 +604,7 @@ static pwr_tStatus IoCardClose( io_tCtx ctx,
{
{
io_sLocal
*
local
=
cp
->
Local
;
io_sLocal
*
local
=
cp
->
Local
;
close
(
local
->
fd
);
close
_device
(
local
);
free
(
cp
->
Local
);
free
(
cp
->
Local
);
// fclose(fp); //Test
// fclose(fp); //Test
...
@@ -611,10 +628,11 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
...
@@ -611,10 +628,11 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
ard_sMsg
msg
;
ard_sMsg
msg
;
io_sChannel
*
chanp
;
io_sChannel
*
chanp
;
if
(
local
->
Reconnect
)
if
(
local
->
Re
opendev
||
local
->
Re
connect
)
return
IO__SUCCESS
;
return
IO__SUCCESS
;
if
(
local
->
ReceiveWriteRespons
)
{
if
(
local
->
ReceiveWriteRespons
)
{
#if 0
// Receive response status from last write
// Receive response status from last write
ard_sMsg rmsg;
ard_sMsg rmsg;
...
@@ -626,6 +644,7 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
...
@@ -626,6 +644,7 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
if ( EVEN(op->Status))
if ( EVEN(op->Status))
op->ErrorCount++;
op->ErrorCount++;
}
}
#endif
local
->
ReceiveWriteRespons
=
0
;
local
->
ReceiveWriteRespons
=
0
;
}
}
...
@@ -675,6 +694,10 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
...
@@ -675,6 +694,10 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
op
->
Status
=
sts
;
op
->
Status
=
sts
;
if
(
EVEN
(
sts
))
{
if
(
EVEN
(
sts
))
{
op
->
ErrorCount
++
;
op
->
ErrorCount
++
;
if
(
sts
==
ARD__NOMSG
&&
op
->
Options
&
pwr_mArduino_OptionsMask_SerialPort
)
{
local
->
Reconnect
=
1
;
}
}
}
else
{
else
{
// printf( "Read: %u %u (%d)\n", rmsg.data[0], rmsg.data[1], sts);
// printf( "Read: %u %u (%d)\n", rmsg.data[0], rmsg.data[1], sts);
...
@@ -739,6 +762,10 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
...
@@ -739,6 +762,10 @@ static pwr_tStatus IoCardRead( io_tCtx ctx,
sts
=
receive
(
local
->
fd
,
local
->
DiPollId
,
&
rmsg
,
local
->
DiSize
,
op
->
Timeout
,
op
);
sts
=
receive
(
local
->
fd
,
local
->
DiPollId
,
&
rmsg
,
local
->
DiSize
,
op
->
Timeout
,
op
);
op
->
Status
=
sts
;
op
->
Status
=
sts
;
if
(
EVEN
(
sts
))
{
if
(
EVEN
(
sts
))
{
if
(
sts
==
ARD__NOMSG
&&
op
->
Options
&
pwr_mArduino_OptionsMask_SerialPort
)
{
local
->
Reconnect
=
1
;
}
op
->
ErrorCount
++
;
op
->
ErrorCount
++
;
}
}
else
{
else
{
...
@@ -835,16 +862,39 @@ static pwr_tStatus IoCardWrite( io_tCtx ctx,
...
@@ -835,16 +862,39 @@ static pwr_tStatus IoCardWrite( io_tCtx ctx,
int
skip_ao
;
int
skip_ao
;
io_sChannel
*
chanp
;
io_sChannel
*
chanp
;
if
(
local
->
Reconnect
)
{
if
(
local
->
Reopendev
)
{
local
->
ReopendevCnt
++
;
if
(
local
->
ReopendevCnt
*
ctx
->
ScanTime
>
5
.
0
)
{
close_device
(
local
);
sts
=
open_and_connect
(
local
,
op
,
cp
);
if
(
EVEN
(
sts
))
{
local
->
Reopendev
=
1
;
local
->
ReopendevCnt
=
0
;
return
IO__SUCCESS
;
}
else
local
->
Reopendev
=
0
;
}
else
return
IO__SUCCESS
;
}
else
if
(
local
->
Reconnect
)
{
local
->
ReconnectCnt
++
;
local
->
ReconnectCnt
++
;
if
(
local
->
ReconnectCnt
*
ctx
->
ScanTime
>
5
.
0
)
{
if
(
local
->
ReconnectCnt
*
ctx
->
ScanTime
>
5
.
0
)
{
sts
=
IoCardClose
(
ctx
,
ap
,
rp
,
cp
);
if
(
op
->
Options
&
pwr_mArduino_OptionsMask_ConnectionRequest
)
{
sts
=
IoCardInit
(
ctx
,
ap
,
rp
,
cp
);
sts
=
send_connect_request
(
local
,
op
,
cp
);
local
=
cp
->
Local
;
if
(
EVEN
(
sts
))
{
if
(
EVEN
(
sts
))
{
local
->
Reconnect
=
1
;
local
->
Reconnect
=
1
;
local
->
ReconnectCnt
=
0
;
return
IO__SUCCESS
;
}
else
local
->
Reconnect
=
0
;
}
}
else
local
->
Reconnect
=
0
;
}
}
else
return
IO__SUCCESS
;
return
IO__SUCCESS
;
}
}
...
@@ -1068,8 +1118,8 @@ static pwr_tStatus IoCardWrite( io_tCtx ctx,
...
@@ -1068,8 +1118,8 @@ static pwr_tStatus IoCardWrite( io_tCtx ctx,
}
}
if
(
sts
<
0
)
{
if
(
sts
<
0
)
{
/* Connection lost, open device again */
/* Connection lost, open device again */
local
->
Re
connect
=
1
;
local
->
Re
opendev
=
1
;
local
->
Re
connect
Cnt
=
0
;
local
->
Re
opendev
Cnt
=
0
;
return
IO__SUCCESS
;
return
IO__SUCCESS
;
}
}
...
...
otherio/wbl/mcomp/src/otherio.wb_load
View file @
51d8a9e3
Volume OtherIO $ClassVolume 0.0.250.10
Volume OtherIO $ClassVolume 0.0.250.10
Body SysBody 01-JAN-1970 01:00:00.00
Body SysBody 01-JAN-1970 01:00:00.00
Attr NextOix = "_X36
8
"
Attr NextOix = "_X36
9
"
Attr NextCix = "_X38"
Attr NextCix = "_X38"
Attr NextTix[0] = "_X15"
Attr NextTix[0] = "_X15"
EndBody
EndBody
...
@@ -484,6 +484,13 @@ Volume OtherIO $ClassVolume 0.0.250.10
...
@@ -484,6 +484,13 @@ Volume OtherIO $ClassVolume 0.0.250.10
Attr Value = 8
Attr Value = 8
EndBody
EndBody
EndObject
EndObject
Object SerialPort $Bit 369 04-MAR-2012 13:51:26.95
Body SysBody 04-MAR-2012 13:51:31.41
Attr Text = "SerialPort"
Attr PgmName = "SerialPort"
Attr Value = 16
EndBody
EndObject
EndObject
EndObject
Object Hilscher_cifX_CommStateEnum $TypeDef 8 11-MAR-2011 09:57:02.13
Object Hilscher_cifX_CommStateEnum $TypeDef 8 11-MAR-2011 09:57:02.13
Body SysBody 11-MAR-2011 09:57:13.54
Body SysBody 11-MAR-2011 09:57:13.54
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment