29
29
#if defined(__cplusplus )
30
30
extern "C"
31
31
{
32
- #endif
32
+ #endif // if defined(__cplusplus)
33
33
34
34
#ifdef RMW_UXRCE_TRANSPORT_IPV4
35
35
#define MAX_IP_LEN 16
36
36
#elif defined(RMW_UXRCE_TRANSPORT_IPV6 )
37
37
#define MAX_IP_LEN 39
38
- #endif
38
+ #endif // ifdef RMW_UXRCE_TRANSPORT_IPV4
39
39
#define MAX_PORT_LEN 5
40
40
#define MAX_SERIAL_DEVICE 50
41
41
42
42
typedef struct rmw_uxrce_transport_params_t
43
43
{
44
44
#if defined(RMW_UXRCE_TRANSPORT_SERIAL )
45
- char serial_device [MAX_SERIAL_DEVICE ];
45
+ char serial_device [MAX_SERIAL_DEVICE ];
46
46
#elif defined(RMW_UXRCE_TRANSPORT_UDP )
47
- char agent_address [MAX_IP_LEN ];
48
- char agent_port [MAX_PORT_LEN ];
47
+ char agent_address [MAX_IP_LEN ];
48
+ char agent_port [MAX_PORT_LEN ];
49
49
#elif defined(RMW_UXRCE_TRANSPORT_CUSTOM )
50
- bool framing ;
50
+ bool framing ;
51
51
void * args ;
52
- open_custom_func open_cb ;
52
+ open_custom_func open_cb ;
53
53
close_custom_func close_cb ;
54
54
write_custom_func write_cb ;
55
- read_custom_func read_cb ;
56
- #endif
57
- uint32_t client_key ;
55
+ read_custom_func read_cb ;
56
+ #endif // if defined(RMW_UXRCE_TRANSPORT_SERIAL)
57
+ uint32_t client_key ;
58
58
} rmw_uxrce_transport_params_t ;
59
59
60
60
/**
@@ -68,8 +68,9 @@ typedef struct rmw_uxrce_transport_params_t
68
68
* \return RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments.
69
69
*/
70
70
rmw_ret_t rmw_uros_init_options (
71
- int argc , const char * const argv [],
72
- rmw_init_options_t * rmw_options );
71
+ int argc ,
72
+ const char * const argv [],
73
+ rmw_init_options_t * rmw_options );
73
74
74
75
/**
75
76
* \brief Fills rmw implementation-specific options with the given parameters.
@@ -79,7 +80,9 @@ rmw_ret_t rmw_uros_init_options(
79
80
* \return RMW_RET_OK If arguments were valid and set in rmw_init_options.
80
81
* \return RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments.
81
82
*/
82
- rmw_ret_t rmw_uros_options_set_serial_device (const char * dev , rmw_init_options_t * rmw_options );
83
+ rmw_ret_t rmw_uros_options_set_serial_device (
84
+ const char * dev ,
85
+ rmw_init_options_t * rmw_options );
83
86
84
87
/**
85
88
* \brief Fills rmw implementation-specific options with the given parameters.
@@ -91,8 +94,9 @@ rmw_ret_t rmw_uros_options_set_serial_device(const char* dev, rmw_init_options_t
91
94
* \return RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments.
92
95
*/
93
96
rmw_ret_t rmw_uros_options_set_udp_address (
94
- const char * ip , const char * port ,
95
- rmw_init_options_t * rmw_options );
97
+ const char * ip ,
98
+ const char * port ,
99
+ rmw_init_options_t * rmw_options );
96
100
97
101
/**
98
102
* \brief Fills rmw implementation-specific options with the autodicovered address of an micro-ROS Agent.
@@ -102,7 +106,8 @@ rmw_ret_t rmw_uros_options_set_udp_address(
102
106
* \return RMW_RET_TIMEOUT If micro-ROS agent autodiscovery is timeout.
103
107
* \return RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments.
104
108
*/
105
- rmw_ret_t rmw_uros_discover_agent (rmw_init_options_t * rmw_options );
109
+ rmw_ret_t rmw_uros_discover_agent (
110
+ rmw_init_options_t * rmw_options );
106
111
107
112
/**
108
113
* \brief Fills rmw implementation-specific options with the given parameters.
@@ -112,7 +117,9 @@ rmw_ret_t rmw_uros_discover_agent(rmw_init_options_t* rmw_options);
112
117
* \return RMW_RET_OK If arguments were valid and set in rmw_init_options.
113
118
* \return RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments.
114
119
*/
115
- rmw_ret_t rmw_uros_options_set_client_key (uint32_t client_key , rmw_init_options_t * rmw_options );
120
+ rmw_ret_t rmw_uros_options_set_client_key (
121
+ uint32_t client_key ,
122
+ rmw_init_options_t * rmw_options );
116
123
117
124
/**
118
125
* \brief Check if micro-ROS Agent is up and running.
@@ -123,7 +130,9 @@ rmw_ret_t rmw_uros_options_set_client_key(uint32_t client_key, rmw_init_options_
123
130
* \return RMW_RET_OK If micro-ROS Agent is available.
124
131
* \return RMW_RET_ERROR If micro-ROS Agent is not available.
125
132
*/
126
- rmw_ret_t rmw_uros_ping_agent (const int timeout_ms , const uint8_t attempts );
133
+ rmw_ret_t rmw_uros_ping_agent (
134
+ const int timeout_ms ,
135
+ const uint8_t attempts );
127
136
128
137
/**
129
138
* \brief Sets the callback functions for continous serialization for a publisher
@@ -133,13 +142,15 @@ rmw_ret_t rmw_uros_ping_agent(const int timeout_ms, const uint8_t attempts);
133
142
* \param[in] serialization_cb callback that should serialize the user part of the message
134
143
*/
135
144
136
- typedef void (* rmw_uros_continous_serialization_size )(uint32_t * topic_length );
137
- typedef void (* rmw_uros_continous_serialization )(ucdrBuffer * ucdr );
145
+ typedef void (* rmw_uros_continous_serialization_size )(
146
+ uint32_t * topic_length );
147
+ typedef void (* rmw_uros_continous_serialization )(
148
+ ucdrBuffer * ucdr );
138
149
139
150
void rmw_uros_set_continous_serialization_callbacks (
140
- rmw_publisher_t * publisher ,
141
- rmw_uros_continous_serialization_size size_cb ,
142
- rmw_uros_continous_serialization serialization_cb );
151
+ rmw_publisher_t * publisher ,
152
+ rmw_uros_continous_serialization_size size_cb ,
153
+ rmw_uros_continous_serialization serialization_cb );
143
154
144
155
#ifdef RMW_UXRCE_TRANSPORT_CUSTOM
145
156
extern rmw_uxrce_transport_params_t rmw_uxrce_transport_default_params ;
@@ -157,17 +168,17 @@ extern rmw_uxrce_transport_params_t rmw_uxrce_transport_default_params;
157
168
* \return RMW_RET_ERROR If invalid.
158
169
*/
159
170
rmw_ret_t rmw_uros_set_custom_transport (
160
- bool framing ,
161
- void * args ,
162
- open_custom_func open_cb ,
163
- close_custom_func close_cb ,
164
- write_custom_func write_cb ,
165
- read_custom_func read_cb );
171
+ bool framing ,
172
+ void * args ,
173
+ open_custom_func open_cb ,
174
+ close_custom_func close_cb ,
175
+ write_custom_func write_cb ,
176
+ read_custom_func read_cb );
166
177
167
178
#endif //RMW_UXRCE_TRANSPORT_CUSTOM
168
179
169
180
#if defined(__cplusplus )
170
181
}
171
- #endif
182
+ #endif // if defined(__cplusplus)
172
183
173
184
#endif // RMW_UROS__OPTIONS_H_
0 commit comments