src
tmc_coe_ros_node.cpp
Go to the documentation of this file.
1
6
#include <signal.h>
7
#include "
tmc_coe_ros.h
"
8
10
11
12
/* Globals */
13
TmcCoeROS
*
p_tmc_coe
=
nullptr
;
14
bool
g_shutdown_signal
=
false
;
15
16
/* Function Prototypes */
17
void
graceful_shutdown
();
18
void
signal_callback_handler
(
int
signum);
19
20
void
graceful_shutdown
()
21
{
22
ROS_INFO_STREAM
(
"> Initiating graceful shutdown..."
);
23
p_tmc_coe
->
deInit
();
24
ROS_INFO_STREAM
(
"> TMC CoE Deinitialized"
);
25
26
delete
p_tmc_coe
;
27
p_tmc_coe
=
nullptr
;
28
29
ros::shutdown
();
30
}
31
32
void
signal_callback_handler
(
int
signum)
33
{
34
ROS_INFO_STREAM
(
"> Caught signal: "
<< signum <<
". Terminating..."
);
35
g_shutdown_signal
=
true
;
36
}
37
38
int
main
(
int
argc,
char
** argv)
39
{
40
41
#ifdef DEBUG
42
if
(
ros::console::set_logger_level
(
ROSCONSOLE_DEFAULT_NAME
,
ros::console::levels::Debug
))
43
{
44
ros::console::notifyLoggerLevelsChanged
();
45
}
46
#endif
47
48
/* Initialize ROS */
49
ros::init
(argc, argv,
"tmc_coe_ros_node"
,
ros::init_options::NoSigintHandler
);
50
ros::NodeHandle
nh;
51
52
try
53
{
54
ROS_INFO_STREAM
(
"> Starting adi_tmc_coe ..."
);
55
signal(SIGINT,
signal_callback_handler
);
56
signal(SIGTERM,
signal_callback_handler
);
57
58
ROS_INFO_STREAM
(
"> Initializing adi_tmc_coe ..."
);
59
ros::AsyncSpinner
spinner(0);
60
p_tmc_coe
=
new
TmcCoeROS
(&nh);
61
62
if
(
p_tmc_coe
->
initialize
())
63
{
64
ROS_INFO_STREAM
(
"> Successfully initialized TMC CoE Interpreter.\n\n"
);
65
spinner.
start
();
66
while
(!
g_shutdown_signal
&&
ros::ok
() && !
p_tmc_coe
->
isInterfaceUnresponsive
())
67
{
68
// Thread running on background
69
}
70
spinner.
stop
();
71
throw
-1;
72
}
73
else
74
{
75
ROS_ERROR_STREAM
(
"[ERROR] Initializing TMC CoE Interpreter failed!, restart node"
);
76
throw
-1;
77
}
78
}
79
catch
(...)
80
{
81
ROS_ERROR_STREAM
(
"[ERROR] Exception encountered. Exiting..."
);
82
graceful_shutdown
();
83
}
84
85
return
(0);
86
}
p_tmc_coe
TmcCoeROS * p_tmc_coe
Definition:
tmc_coe_ros_node.cpp:13
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
graceful_shutdown
void graceful_shutdown()
Definition:
tmc_coe_ros_node.cpp:20
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
ros::ok
ROSCPP_DECL bool ok()
TmcCoeROS
Definition:
tmc_coe_ros.h:28
TmcCoeROS::initialize
bool initialize()
Definition:
tmc_coe_ros.cpp:47
TmcCoeROS::isInterfaceUnresponsive
bool isInterfaceUnresponsive()
Definition:
tmc_coe_ros.cpp:407
ros::console::levels::Debug
Debug
g_shutdown_signal
bool g_shutdown_signal
Definition:
tmc_coe_ros_node.cpp:14
tmc_coe_ros.h
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
main
int main(int argc, char **argv)
Definition:
tmc_coe_ros_node.cpp:38
ros::AsyncSpinner::stop
void stop()
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
TmcCoeROS::deInit
void deInit()
Definition:
tmc_coe_ros.cpp:400
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
ros::init_options::NoSigintHandler
NoSigintHandler
signal_callback_handler
void signal_callback_handler(int signum)
Definition:
tmc_coe_ros_node.cpp:32
ros::NodeHandle
adi_tmc_coe
Author(s):
autogenerated on Sun Feb 2 2025 03:07:24