Main Page
Namespaces
Classes
Files
File List
File Members
src
sick_tim310.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2013, Osnabrück University
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of Osnabrück University nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*
29
* Created on: 24.05.2012
30
*
31
* Authors:
32
* Jochen Sprickerhof <jochen@sprickerhof.de>
33
* Martin Günther <mguenthe@uos.de>
34
*
35
* Based on the TiM communication example by SICK AG.
36
*
37
*/
38
39
#include <
sick_tim/sick_tim_common_usb.h
>
40
#include <
sick_tim/sick_tim_common_mockup.h
>
41
#include <
sick_tim/sick_tim310_parser.h
>
42
43
int
main
(
int
argc,
char
**argv)
44
{
45
ros::init
(argc, argv,
"sick_tim310"
);
46
ros::NodeHandle
nhPriv(
"~"
);
47
48
bool
subscribe_datagram;
49
int
device_number;
50
nhPriv.
param
(
"subscribe_datagram"
, subscribe_datagram,
false
);
51
nhPriv.
param
(
"device_number"
, device_number, 0);
52
53
sick_tim::SickTim310Parser
*
parser
=
new
sick_tim::SickTim310Parser
();
54
55
sick_tim::SickTimCommon
*
s
= NULL;
56
57
int
result =
sick_tim::ExitError
;
58
while
(
ros::ok
())
59
{
60
// Atempt to connect/reconnect
61
if
(subscribe_datagram)
62
s =
new
sick_tim::SickTimCommonMockup
(parser);
63
else
64
s =
new
sick_tim::SickTimCommonUsb
(parser, device_number);
65
result = s->
init
();
66
67
while
(
ros::ok
() && (result ==
sick_tim::ExitSuccess
)){
68
ros::spinOnce
();
69
result = s->
loopOnce
();
70
}
71
72
delete
s;
73
74
if
(result ==
sick_tim::ExitFatal
)
75
return
result;
76
77
if
(
ros::ok
() && !subscribe_datagram)
78
ros::Duration
(1.0).
sleep
();
// Only attempt USB connections once per second
79
}
80
81
delete
parser;
82
return
result;
83
}
sick_tim::ExitError
Definition:
abstract_parser.h:47
sick_tim310_parser.h
ros::NodeHandle
sick_tim::SickTim310Parser
Definition:
sick_tim310_parser.h:43
s
XmlRpcServer s
ros::Duration::sleep
bool sleep() const
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sick_tim::SickTimCommon
Definition:
sick_tim_common.h:63
sick_tim::ExitFatal
Definition:
abstract_parser.h:48
sick_tim_common_usb.h
sick_tim_common_mockup.h
ros::NodeHandle::param
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
sick_tim::SickTimCommonUsb
Definition:
sick_tim_common_usb.h:52
ros::ok
ROSCPP_DECL bool ok()
sick_tim::SickTimCommon::init
virtual int init()
Definition:
sick_tim_common.cpp:145
sick_tim::ExitSuccess
Definition:
abstract_parser.h:46
main
int main(int argc, char **argv)
Definition:
sick_tim310.cpp:43
ros::Duration
parser
parser
sick_tim::SickTimCommon::loopOnce
virtual int loopOnce()
Definition:
sick_tim_common.cpp:290
ros::spinOnce
ROSCPP_DECL void spinOnce()
sick_tim::SickTimCommonMockup
Definition:
sick_tim_common_mockup.h:51
sick_tim
Author(s): Jochen Sprickerhof
, Martin Günther
, Sebastian Pütz
autogenerated on Wed Jun 17 2020 04:05:36