Main Page
Namespaces
Namespace List
Namespace Members
All
c
d
e
f
g
l
m
p
r
s
Functions
Variables
Classes
Class List
Class Hierarchy
Class Members
All
_
a
b
c
d
e
f
h
i
j
l
m
n
o
p
r
s
t
u
~
Functions
_
a
b
c
d
e
i
j
m
o
p
r
s
t
u
~
Variables
_
b
c
d
e
f
h
i
j
l
m
n
p
r
s
t
Files
File List
File Members
All
b
c
d
e
g
i
j
l
m
p
r
s
t
v
w
Functions
c
d
g
i
j
l
m
p
r
s
t
w
Typedefs
src
main.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
3
#include "
ffi/callback_from_rust.h
"
4
#include "
ffi/rust_functions.h
"
5
6
int
main
(
int
argc,
char
** argv) {
7
// 日本語を出力する場合のため
8
setlocale(LC_CTYPE,
"ja_JP.UTF-8"
);
9
ros::init
(argc, argv,
"skyway"
);
10
ros::AsyncSpinner
spinner(4);
11
spinner.
start
();
12
13
// Rust側からC++側の関数を呼び出すためのセッティング
14
register_logger
(
log_debug_c
,
log_info_c
,
log_warn_c
,
log_err_c
);
15
register_program_state
(
is_ok_c
,
is_shutting_down_c
,
ros_sleep_c
,
16
wait_for_shutdown_c
,
shutdown_c
);
17
// Rust側の処理開始
18
run_response_t
response
=
run
();
19
20
if
(
response
.flag) {
21
// Rust側の処理が正常に開始した
22
ROS_DEBUG
(
"program starts successfully"
);
23
Injector<CallbackFromRust> apiInjector(
getCallbackFromRustComponent
);
24
std::shared_ptr<CallbackFromRust> ffi =
25
apiInjector.get<std::shared_ptr<CallbackFromRust>>();
26
27
//メインスレッドはここで止めてあとはSeviceとActionからの処理を待ち受け続ける
28
ros::waitForShutdown
();
29
}
else
{
30
// Rust側の処理が正常に開始しなかった
31
// registerを忘れているケースなので通常発生しない
32
ROS_ERROR
(
"some errors occurred"
);
33
}
34
35
spinner.
stop
();
36
ros::shutdown
();
37
// Rust側のthreadが終了するまで待機する
38
if
(
response
.flag) {
39
ROS_DEBUG
(
"Waiting for Rust side thread to finish"
);
40
join_handler
(
response
.handler);
41
}
42
43
return
0;
44
}
response
const std::string response
shutdown_c
void shutdown_c()
Definition:
ros_functions.cpp:34
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
log_err_c
void log_err_c(char *message)
Definition:
ros_functions.cpp:24
ros::AsyncSpinner::start
void start()
ros.h
register_logger
void register_logger(void_char_func debug, void_char_func info, void_char_func warn, void_char_func error)
ros::AsyncSpinner
main
int main(int argc, char **argv)
Definition:
main.cpp:6
ros::shutdown
ROSCPP_DECL void shutdown()
wait_for_shutdown_c
void wait_for_shutdown_c()
Definition:
ros_functions.cpp:33
ROS_DEBUG
#define ROS_DEBUG(...)
ros_sleep_c
void ros_sleep_c(double dur)
Definition:
ros_functions.cpp:32
log_info_c
void log_info_c(char *message)
Definition:
ros_functions.cpp:16
rust_functions.h
ros::AsyncSpinner::stop
void stop()
join_handler
void join_handler(void *handler)
log_warn_c
void log_warn_c(char *message)
Definition:
ros_functions.cpp:20
is_ok_c
bool is_ok_c()
Definition:
ros_functions.cpp:30
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
ROS_ERROR
#define ROS_ERROR(...)
log_debug_c
void log_debug_c(char *message)
Definition:
ros_functions.cpp:12
register_program_state
void register_program_state(bool_void_func is_running_c, bool_void_func is_shutting_down_c, void_double_func sleep_c, void_void_func wait_for_shutdown_c, void_void_func shutdown_c)
getCallbackFromRustComponent
Component< CallbackFromRust > getCallbackFromRustComponent()
Definition:
callback_from_rust.cpp:81
run
run_response_t run()
callback_from_rust.h
run_response_t
Definition:
common.h:35
is_shutting_down_c
bool is_shutting_down_c()
Definition:
ros_functions.cpp:31
skyway
Author(s): Toshiya Nakakura
autogenerated on Thu Oct 26 2023 02:42:21