xsscanner.cpp
Go to the documentation of this file.
1 
2 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without modification,
6 // are permitted provided that the following conditions are met:
7 //
8 // 1. Redistributions of source code must retain the above copyright notice,
9 // this list of conditions, and the following disclaimer.
10 //
11 // 2. Redistributions in binary form must reproduce the above copyright notice,
12 // this list of conditions, and the following disclaimer in the documentation
13 // and/or other materials provided with the distribution.
14 //
15 // 3. Neither the names of the copyright holders nor the names of their contributors
16 // may be used to endorse or promote products derived from this software without
17 // specific prior written permission.
18 //
19 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
20 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
22 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
24 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
25 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
26 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
28 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
29 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
30 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
31 //
32 
33 
34 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
35 // All rights reserved.
36 //
37 // Redistribution and use in source and binary forms, with or without modification,
38 // are permitted provided that the following conditions are met:
39 //
40 // 1. Redistributions of source code must retain the above copyright notice,
41 // this list of conditions, and the following disclaimer.
42 //
43 // 2. Redistributions in binary form must reproduce the above copyright notice,
44 // this list of conditions, and the following disclaimer in the documentation
45 // and/or other materials provided with the distribution.
46 //
47 // 3. Neither the names of the copyright holders nor the names of their contributors
48 // may be used to endorse or promote products derived from this software without
49 // specific prior written permission.
50 //
51 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
52 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
53 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
54 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
55 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
56 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
57 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
58 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
59 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
60 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
61 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
62 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
63 //
64 
65 #include "xsscanner.h"
66 #include "scanner.h"
67 #include "enumerateusbdevices.h"
68 
74 void XsScanner_scanPorts_int(XsPortInfoArray* ports, XsBaudRate baudrate, int singleScanTimeout, int ignoreNonXsensDevices, int detectRs485)
75 {
76  LOGXSSCAN(__FUNCTION__ << " baudrate " << baudrate << " singleScanTimeout " << singleScanTimeout << " ignoreNonXsensDevices " << ignoreNonXsensDevices << " detectRs485 " << detectRs485);
77 
78  assert(ports != nullptr);
79  if (!ports)
80  return;
81 
82  XsPortInfoArray tmp;
83  Scanner::Accessor accessor;
84  accessor.scanner().xsScanPorts(tmp, baudrate, (uint32_t) singleScanTimeout, ignoreNonXsensDevices != 0, detectRs485 != 0);
85  if (tmp.size())
86  ports->assign(tmp.size(), &tmp[0]);
87  else
88  ports->clear();
89 }
90 
92 int XsScanner_scanPort_int(XsPortInfo* port, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
93 {
94  assert(port != nullptr);
95  if (!port)
96  return 0;
97 
98  Scanner::Accessor accessor;
99  return accessor.scanner().xsScanPort(*port, baudrate, (uint32_t)singleScanTimeout, detectRs485 != 0) ? 1 : 0;
100 }
101 
107 void XsScanner_enumerateSerialPorts_int(XsPortInfoArray* ports, int ignoreNonXsensDevices)
108 {
109  LOGXSSCAN(__FUNCTION__ << " ignoreNonXsensDevices " << ignoreNonXsensDevices);
110 
111  assert(ports != nullptr);
112  if (!ports)
113  return;
114 
115  XsPortInfoArray tmp;
116  Scanner::Accessor accessor;
117  accessor.scanner().xsEnumerateSerialPorts(tmp, ignoreNonXsensDevices != 0);
118  if (tmp.size())
119  ports->assign(tmp.size(), &tmp[0]);
120  else
121  ports->clear();
122 }
123 
124 extern "C" {
125 
132  {
134  }
135 
144  void XsScanner_scanPorts(XsPortInfoArray* ports, XsBaudRate baudrate, int singleScanTimeout, int ignoreNonXsensDevices, int detectRs485)
145  {
146  LOGXSSCAN(__FUNCTION__ << " baudrate " << baudrate << " singleScanTimeout " << singleScanTimeout << " ignoreNonXsensDevices " << ignoreNonXsensDevices << " detectRs485 " << detectRs485);
147  XsScanner_scanPorts_int(ports, baudrate, singleScanTimeout, ignoreNonXsensDevices, detectRs485);
148  }
149 
158  int XsScanner_scanPort(XsPortInfo* port, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
159  {
160  LOGXSSCAN(__FUNCTION__ << " baudrate " << baudrate << " singleScanTimeout " << singleScanTimeout << " detectRs485 " << detectRs485);
161  return XsScanner_scanPort_int(port, baudrate, singleScanTimeout, detectRs485);
162  }
163 
165  void XsScanner_enumerateSerialPorts(XsPortInfoArray* ports, int ignoreNonXsensDevices)
166  {
167  LOGXSSCAN(__FUNCTION__ << " ignoreNonXsensDevices " << ignoreNonXsensDevices);
168  XsScanner_enumerateSerialPorts_int(ports, ignoreNonXsensDevices);
169  }
170 
178  void XsScanner_filterResponsiveDevices(XsPortInfoArray* ports, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
179  {
180  LOGXSSCAN(__FUNCTION__ << " baudrate " << baudrate << " singleScanTimeout " << singleScanTimeout << " detectRs485 " << detectRs485);
181  assert(ports != nullptr);
182  if (!ports)
183  return;
184 
185  XsPortInfoArray tmp;
186  for (XsSize i = 0; i < ports->size(); ++i)
187  tmp.push_back(ports->at(i));
188  Scanner::Accessor accessor;
189  if (accessor.scanner().xsFilterResponsiveDevices(tmp, baudrate, (uint32_t) singleScanTimeout, detectRs485 != 0))
190  {
191  if (tmp.size())
192  {
193  ports->assign(tmp.size(), &tmp[0]);
194  return;
195  }
196  }
197  ports->clear();
198  }
199 
205  {
206  LOGXSSCAN(__FUNCTION__);
207 
208  assert(ports != nullptr);
209  if (!ports)
210  return;
211 
212  XsPortInfoArray tmp;
214  if (tmp.size())
215  ports->assign(tmp.size(), &tmp[0]);
216  else
217  ports->clear();
218  }
219 
226  {
227  LOGXSSCAN(__FUNCTION__);
228 
229  assert(hub != nullptr && port != nullptr);
230  if (!hub || !port)
231  return;
232 
233  Scanner::Accessor accessor;
234  *hub = accessor.scanner().xsScanUsbHub(*port);
235  }
236 
238  {
239  LOGXSSCAN(__FUNCTION__);
240  assert(ports != nullptr);
241  if (!ports)
242  return;
243 
244  XsPortInfoArray tmp;
245 
246  Scanner::Accessor accessor;
247  accessor.scanner().xsEnumerateNetworkDevices(tmp);
248  ports->swap(tmp);
249  }
250 
252  {
253  LOGXSSCAN(__FUNCTION__);
254  assert(ports != nullptr);
255  if (!ports)
256  return;
257 
258  XsPortInfoArray tmp;
259 
260  Scanner::Accessor accessor;
261  accessor.scanner().xsEnumerateBluetoothDevices(tmp);
262  ports->swap(tmp);
263  }
264 
269  {
270  LOGXSSCAN(__FUNCTION__);
272  }
273 
274 } // extern "C"
XsScanner::XsScanner_scanPorts
void XsScanner_scanPorts(XsPortInfoArray *ports, XsBaudRate baudrate, int singleScanTimeout, int ignoreNonXsensDevices, int detectRs485)
Scan all ports for Xsens devices.
Definition: xsscanner.cpp:144
XsScannerNamespace::abortPortScan
volatile std::atomic_bool abortPortScan
Definition: scanner.cpp:98
Scanner::xsScanPort
bool xsScanPort(XsPortInfo &portInfo, XsBaudRate baud, uint32_t singleScanTimeout, bool detectRs485)
Scan a single COM port for connected Xsens devices.
Definition: scanner.cpp:224
XsScanner_scanPorts_int
void XsScanner_scanPorts_int(XsPortInfoArray *ports, XsBaudRate baudrate, int singleScanTimeout, int ignoreNonXsensDevices, int detectRs485)
Scan all ports for Xsens devices.
Definition: xsscanner.cpp:74
XsScanner_setScanLogCallback
void XsScanner_setScanLogCallback(XsScanLogCallbackFunc cb)
Set a callback function for scan log progress and problem reporting.
Definition: xsscanner.cpp:131
XsScanner::XsScanner_abortScan
void XsScanner_abortScan(void)
Abort the currently running port scan(s)
Definition: xsscanner.cpp:268
XsScanner::XsScanner_scanPort
int XsScanner_scanPort(XsPortInfo *port, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
Scan a single port for Xsens devices.
Definition: xsscanner.cpp:158
XsScanner::XsScanner_enumerateSerialPorts_int
void XsScanner_enumerateSerialPorts_int(XsPortInfoArray *ports, int ignoreNonXsensDevices)
List all serial ports without scanning.
Definition: xsscanner.cpp:107
enumerateusbdevices.h
XsScanLogCallbackFunc
void(* XsScanLogCallbackFunc)(struct XsString const *)
Defines the callback type that can be supplied to XsScanner_setScanLogCallback.
Definition: xsscanner.h:91
XsScanner::XsScanner_scanUsbHub
void XsScanner_scanUsbHub(XsUsbHubInfo *hub, const XsPortInfo *port)
Determine the USB hub that port is attached to.
Definition: xsscanner.cpp:225
Scanner::xsFilterResponsiveDevices
bool xsFilterResponsiveDevices(XsPortInfoArray &ports, XsBaudRate baudrate, uint32_t singleScanTimeout, bool detectRs485)
Filter responsive devices.
Definition: scanner.cpp:339
XsBaudRate
enum XsBaudRate XsBaudRate
Communication speed.
Definition: xsbaud.h:81
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
XsPortInfo
Contains a descriptor for opening a communication port to an Xsens device.
Definition: xsportinfo.h:128
Scanner::xsEnumerateSerialPorts
bool xsEnumerateSerialPorts(XsPortInfoArray &ports, bool ignoreNonXsensDevices)
Enumerate the serial ports.
Definition: scanner.cpp:406
Scanner::xsEnumerateBluetoothDevices
virtual bool xsEnumerateBluetoothDevices(XsPortInfoArray &ports)
Enumerates a bluetooth device.
Definition: scanner.cpp:599
XsScanner_enumerateSerialPorts
void XsScanner_enumerateSerialPorts(XsPortInfoArray *ports, int ignoreNonXsensDevices)
List all serial ports without scanning.
Definition: xsscanner.cpp:165
Scanner::xsScanPorts
virtual bool xsScanPorts(XsPortInfoArray &ports, XsBaudRate baudrate, uint32_t singleScanTimeout, bool ignoreNonXsensDevices, bool detectRs485)
Scan serial ports for connected Xsens devices.
Definition: scanner.cpp:315
XsSize
size_t XsSize
XsSize must be unsigned number!
Definition: xstypedefs.h:74
Scanner::xsScanUsbHub
XsUsbHubInfo xsScanUsbHub(const XsPortInfo &portInfo)
Get information about the hub configuration.
Definition: scanner.cpp:879
xsEnumerateUsbDevices
bool xsEnumerateUsbDevices(XsPortInfoArray &ports)
Enumerate Xsens USB devices.
Definition: enumerateusbdevices.cpp:145
XsUsbHubInfo
A structure that wraps USB hub information.
Definition: xsusbhubinfo.h:99
XsPortInfoArray
A list of XsPortInfo values.
XsScanner_scanPort_int
int XsScanner_scanPort_int(XsPortInfo *port, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
Scan a single port for Xsens devices.
Definition: xsscanner.cpp:92
XsScanner_enumerateNetworkDevices
void XsScanner_enumerateNetworkDevices(XsPortInfoArray *ports)
Definition: xsscanner.cpp:237
XsScanner_enumerateBluetoothDevices
void XsScanner_enumerateBluetoothDevices(XsPortInfoArray *ports)
Definition: xsscanner.cpp:251
LOGXSSCAN
#define LOGXSSCAN(msg)
Definition: scanner.h:123
Scanner::setScanLogCallback
static void setScanLogCallback(XsScanLogCallbackFunc cb)
Set a callback function for scan log progress and problem reporting.
Definition: scanner.cpp:131
XsScanner::XsScanner_enumerateUsbDevices
void XsScanner_enumerateUsbDevices(XsPortInfoArray *ports)
List all compatible USB ports without scanning.
Definition: xsscanner.cpp:204
scanner.h
Scanner::xsEnumerateNetworkDevices
virtual bool xsEnumerateNetworkDevices(XsPortInfoArray &ports)
Enumerates a network device.
Definition: scanner.cpp:589
XsScanner::XsScanner_filterResponsiveDevices
void XsScanner_filterResponsiveDevices(XsPortInfoArray *ports, XsBaudRate baudrate, int singleScanTimeout, int detectRs485)
Scan the supplied ports for Xsens devices.
Definition: xsscanner.cpp:178
Scanner::Accessor::scanner
Scanner & scanner() const
Definition: scanner.cpp:110
xsscanner.h
Scanner::Accessor
An accessor class for scanner.
Definition: scanner.h:88


xsens_mti_driver
Author(s):
autogenerated on Sun Sep 3 2023 02:43:20