-
Notifications
You must be signed in to change notification settings - Fork 18
/
Copy pathmros2.h
108 lines (87 loc) · 1.71 KB
/
mros2.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
#ifndef MROS2_MROS2_H
#define MROS2_MROS2_H
#include <string>
#include "rtps/rtps.h"
#ifndef __MBED__
#include "lwip.h"
#endif /* __MBED__ */
#include "mros2/logging.h"
/* Statement to avoid link error */
#ifdef __cplusplus
extern void *__dso_handle;
#endif
namespace rtps
{
namespace Config
{
extern std::array<uint8_t, 4> IP_ADDRESS;
}
}
namespace mros2
{
void init(int argc, char *argv[]);
#ifdef __cplusplus
extern "C"
{
#endif
void mros2_init(void *arg);
#ifdef __cplusplus
}
#endif
class Node;
class Publisher;
class Subscriber;
/* TODO: move to node.h/cpp? */
class Node
{
public:
static Node create_node(
std::string node_name);
template <class T>
Publisher create_publisher(
std::string topic_name,
int qos);
template <class T>
Subscriber create_subscription(
std::string topic_name,
int qos,
void (*fp)(T *));
std::string node_name;
rtps::Participant *part;
private:
};
class Publisher
{
public:
std::string topic_name;
template <class T>
void publish(T &msg);
};
class Subscriber
{
public:
std::string topic_name;
template <class T>
static void callback_handler(
void *callee,
const rtps::ReaderCacheChange &cacheChange);
void (*cb_fp)(intptr_t);
private:
};
void spin();
#ifdef __MBED__
int setIPAddrRTPS(std::array<uint8_t, 4> ipaddr);
#endif /* __MBED__ */
} /* namespace mros2 */
#ifndef __MBED__
extern "C" int mros2_setIPAddrRTPS(uint32_t ipaddr);
#endif /* __MBED__ */
namespace message_traits
{
template <class T>
struct TypeName
{
static const char *value();
};
} /* namespace message_traits */
#endif /* MROS2_MROS2_H */