|
| 1 | +# micro-ROS RMW API |
| 2 | + |
| 3 | +## Functions |
| 4 | + |
| 5 | +| | Name | |
| 6 | +| --------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | |
| 7 | +| void | **[rmw_uros_set_continous_serialization_callbacks](#function-rmw_uros_set_continous_serialization_callbacks)**(rmw_publisher_t * publisher, rmw_uros_continous_serialization_size size_cb, rmw_uros_continous_serialization serialization_cb)<br>Sets the callback functions for continous serialization for a publisher. | |
| 8 | +| rmw_ret_t | **[rmw_uros_set_custom_transport](#function-rmw_uros_set_custom_transport)**(bool framing, void * args, open_custom_func open_cb, close_custom_func close_cb, write_custom_func write_cb, read_custom_func read_cb)<br>Check if micro-ROS Agent answers to micro-ROS client. | |
| 9 | +| rmw_ret_t | **[rmw_uros_discover_agent](#function-rmw_uros_discover_agent)**(rmw_init_options_t * rmw_options)<br>Fills rmw implementation-specific options with the autodicovered address of an micro-ROS Agent. | |
| 10 | +| rmw_ret_t | **[rmw_uros_init_options](#function-rmw_uros_init_options)**(int argc, const char *const argv[], rmw_init_options_t * rmw_options)<br>Parses command line args and fills rmw implementation-specific options. | |
| 11 | +| rmw_ret_t | **[rmw_uros_options_set_serial_device](#function-rmw_uros_options_set_serial_device)**(const char * dev, rmw_init_options_t * rmw_options)<br>Fills rmw implementation-specific options with the given parameters. | |
| 12 | +| rmw_ret_t | **[rmw_uros_options_set_udp_address](#function-rmw_uros_options_set_udp_address)**(const char * ip, const char * port, rmw_init_options_t * rmw_options)<br>Fills rmw implementation-specific options with the given parameters. | |
| 13 | +| rmw_ret_t | **[rmw_uros_options_set_client_key](#function-rmw_uros_options_set_client_key)**(uint32_t client_key, rmw_init_options_t * rmw_options)<br>Fills rmw implementation-specific options with the given parameters. | |
| 14 | +| rmw_ret_t | **[rmw_uros_ping_agent](#function-rmw_uros_ping_agent)**(const int timeout_ms, const uint8_t attempts)<br>Check if micro-ROS Agent is up and running. | |
| 15 | +| bool | **[rmw_uros_epoch_synchronized](#function-rmw_uros_epoch_synchronized)**()<br>Returns the time synchronization state of the epoch time. | |
| 16 | +| int64_t | **[rmw_uros_epoch_millis](#function-rmw_uros_epoch_millis)**()<br>Returns the epoch time in milliseconds taking into account the offset computed during the time synchronization. | |
| 17 | +| int64_t | **[rmw_uros_epoch_nanos](#function-rmw_uros_epoch_nanos)**()<br>Returns the epoch time in nanoseconds taking into account the offset computed during the time synchronization. | |
| 18 | +| rmw_ret_t | **[rmw_uros_sync_session](#function-rmw_uros_sync_session)**(const int timeout_ms)<br>Synchronizes the session time using the NTP protocol. | |
| 19 | + |
| 20 | + |
| 21 | +## Functions Documentation |
| 22 | + |
| 23 | +### function rmw_uros_set_continous_serialization_callbacks |
| 24 | + |
| 25 | +```cpp |
| 26 | +void rmw_uros_set_continous_serialization_callbacks( |
| 27 | + rmw_publisher_t * publisher, |
| 28 | + rmw_uros_continous_serialization_size size_cb, |
| 29 | + rmw_uros_continous_serialization serialization_cb |
| 30 | +) |
| 31 | +``` |
| 32 | + |
| 33 | +Sets the callback functions for continous serialization for a publisher. |
| 34 | + |
| 35 | +**Parameters**: |
| 36 | + |
| 37 | + * **publisher** publisher where continous serialization is being configured |
| 38 | + * **size_cb** callback that should modify the total serialization size |
| 39 | + * **serialization_cb** callback that should serialize the user part of the message |
| 40 | + |
| 41 | + |
| 42 | +### function rmw_uros_set_custom_transport |
| 43 | + |
| 44 | +```cpp |
| 45 | +rmw_ret_t rmw_uros_set_custom_transport( |
| 46 | + bool framing, |
| 47 | + void * args, |
| 48 | + open_custom_func open_cb, |
| 49 | + close_custom_func close_cb, |
| 50 | + write_custom_func write_cb, |
| 51 | + read_custom_func read_cb |
| 52 | +) |
| 53 | +``` |
| 54 | + |
| 55 | +Check if micro-ROS Agent answers to micro-ROS client. |
| 56 | + |
| 57 | +**Parameters**: |
| 58 | + |
| 59 | + * **framing** Enable XRCE framing. |
| 60 | + * **args** Arguments for open function. |
| 61 | + * **open_cb** Open transport callback. |
| 62 | + * **close_cb** Close transport callback. |
| 63 | + * **write_cb** Write transport callback. |
| 64 | + * **read_cb** Read transport callback. |
| 65 | + |
| 66 | + |
| 67 | +**Return**: |
| 68 | + |
| 69 | + * RMW_RET_OK If correct. |
| 70 | + * RMW_RET_ERROR If invalid. |
| 71 | + |
| 72 | + |
| 73 | +### function rmw_uros_discover_agent |
| 74 | + |
| 75 | +```cpp |
| 76 | +rmw_ret_t rmw_uros_discover_agent( |
| 77 | + rmw_init_options_t * rmw_options |
| 78 | +) |
| 79 | +``` |
| 80 | + |
| 81 | +Fills rmw implementation-specific options with the autodicovered address of an micro-ROS Agent. |
| 82 | + |
| 83 | +**Parameters**: |
| 84 | + |
| 85 | + * **rmw_options** Updated options with rmw specifics. |
| 86 | + |
| 87 | + |
| 88 | +**Return**: |
| 89 | + |
| 90 | + * RMW_RET_OK If arguments were valid and set in rmw_init_options. |
| 91 | + * RMW_RET_TIMEOUT If micro-ROS agent autodiscovery is timeout. |
| 92 | + * RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments. |
| 93 | + |
| 94 | + |
| 95 | +### function rmw_uros_init_options |
| 96 | + |
| 97 | +```cpp |
| 98 | +rmw_ret_t rmw_uros_init_options( |
| 99 | + int argc, |
| 100 | + const char *const argv[], |
| 101 | + rmw_init_options_t * rmw_options |
| 102 | +) |
| 103 | +``` |
| 104 | + |
| 105 | +Parses command line args and fills rmw implementation-specific options. |
| 106 | + |
| 107 | +**Parameters**: |
| 108 | + |
| 109 | + * **argc** Number of arguments. |
| 110 | + * **argv** Arguments. |
| 111 | + * **rmw_options** Updated options with rmw specifics. |
| 112 | + |
| 113 | + |
| 114 | +**Return**: |
| 115 | + |
| 116 | + * RMW_RET_OK If arguments were valid and set in rmw_init_options. |
| 117 | + * RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments. |
| 118 | + |
| 119 | + |
| 120 | +`rmw_init_options allocator` is used to allocate the specific rmw options. |
| 121 | + |
| 122 | + |
| 123 | +### function rmw_uros_options_set_serial_device |
| 124 | + |
| 125 | +```cpp |
| 126 | +rmw_ret_t rmw_uros_options_set_serial_device( |
| 127 | + const char * dev, |
| 128 | + rmw_init_options_t * rmw_options |
| 129 | +) |
| 130 | +``` |
| 131 | + |
| 132 | +Fills rmw implementation-specific options with the given parameters. |
| 133 | + |
| 134 | +**Parameters**: |
| 135 | + |
| 136 | + * **dev** Serial device. |
| 137 | + * **rmw_options** Updated options with rmw specifics. |
| 138 | + |
| 139 | + |
| 140 | +**Return**: |
| 141 | + |
| 142 | + * RMW_RET_OK If arguments were valid and set in rmw_init_options. |
| 143 | + * RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments. |
| 144 | + |
| 145 | + |
| 146 | +### function rmw_uros_options_set_udp_address |
| 147 | + |
| 148 | +```cpp |
| 149 | +rmw_ret_t rmw_uros_options_set_udp_address( |
| 150 | + const char * ip, |
| 151 | + const char * port, |
| 152 | + rmw_init_options_t * rmw_options |
| 153 | +) |
| 154 | +``` |
| 155 | + |
| 156 | +Fills rmw implementation-specific options with the given parameters. |
| 157 | + |
| 158 | +**Parameters**: |
| 159 | + |
| 160 | + * **ip** Agent IP address. |
| 161 | + * **port** Agent UDP port. |
| 162 | + * **rmw_options** Updated options with rmw specifics. |
| 163 | + |
| 164 | + |
| 165 | +**Return**: |
| 166 | + |
| 167 | + * RMW_RET_OK If arguments were valid and set in rmw_init_options. |
| 168 | + * RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments. |
| 169 | + |
| 170 | + |
| 171 | +### function rmw_uros_options_set_client_key |
| 172 | + |
| 173 | +```cpp |
| 174 | +rmw_ret_t rmw_uros_options_set_client_key( |
| 175 | + uint32_t client_key, |
| 176 | + rmw_init_options_t * rmw_options |
| 177 | +) |
| 178 | +``` |
| 179 | + |
| 180 | +Fills rmw implementation-specific options with the given parameters. |
| 181 | + |
| 182 | +**Parameters**: |
| 183 | + |
| 184 | + * **client_key** MicroXRCE-DDS client key. |
| 185 | + * **rmw_options** Updated options with rmw specifics. |
| 186 | + |
| 187 | + |
| 188 | +**Return**: |
| 189 | + |
| 190 | + * RMW_RET_OK If arguments were valid and set in rmw_init_options. |
| 191 | + * RMW_RET_INVALID_ARGUMENT If rmw_init_options is not valid or unexpected arguments. |
| 192 | + |
| 193 | + |
| 194 | +### function rmw_uros_ping_agent |
| 195 | + |
| 196 | +```cpp |
| 197 | +rmw_ret_t rmw_uros_ping_agent( |
| 198 | + const int timeout_ms, |
| 199 | + const uint8_t attempts |
| 200 | +) |
| 201 | +``` |
| 202 | + |
| 203 | +Check if micro-ROS Agent is up and running. |
| 204 | + |
| 205 | +**Parameters**: |
| 206 | + |
| 207 | + * **timeout_ms** Timeout in ms (per attempt). |
| 208 | + * **attempts** Number of tries before considering the ping as failed. |
| 209 | + |
| 210 | + |
| 211 | +**Return**: |
| 212 | + |
| 213 | + * RMW_RET_OK If micro-ROS Agent is available. |
| 214 | + * RMW_RET_ERROR If micro-ROS Agent is not available. |
| 215 | + |
| 216 | + |
| 217 | +This function can be called even when the micro-ROS context has not yet been initialized by the application logics. |
| 218 | + |
| 219 | + |
| 220 | +### function rmw_uros_epoch_synchronized |
| 221 | + |
| 222 | +```cpp |
| 223 | +bool rmw_uros_epoch_synchronized() |
| 224 | +``` |
| 225 | + |
| 226 | +Returns the time synchronization state of the epoch time. |
| 227 | + |
| 228 | +**Return**: true if last time synchronization succeded and false otherwise |
| 229 | + |
| 230 | +### function rmw_uros_epoch_millis |
| 231 | + |
| 232 | +```cpp |
| 233 | +int64_t rmw_uros_epoch_millis() |
| 234 | +``` |
| 235 | + |
| 236 | +Returns the epoch time in milliseconds taking into account the offset computed during the time synchronization. |
| 237 | + |
| 238 | +**Return**: |
| 239 | + |
| 240 | + * epoch time in milliseconds. |
| 241 | + * 0 if session is not initialized. |
| 242 | + |
| 243 | + |
| 244 | +### function rmw_uros_epoch_nanos |
| 245 | + |
| 246 | +```cpp |
| 247 | +int64_t rmw_uros_epoch_nanos() |
| 248 | +``` |
| 249 | + |
| 250 | +Returns the epoch time in nanoseconds taking into account the offset computed during the time synchronization. |
| 251 | + |
| 252 | +**Return**: |
| 253 | + |
| 254 | + * epoch time in nanoseconds. |
| 255 | + * 0 if session is not initialized. |
| 256 | + |
| 257 | + |
| 258 | +### function rmw_uros_sync_session |
| 259 | + |
| 260 | +```cpp |
| 261 | +rmw_ret_t rmw_uros_sync_session( |
| 262 | + const int timeout_ms |
| 263 | +) |
| 264 | +``` |
| 265 | + |
| 266 | +Synchronizes the session time using the NTP protocol. |
| 267 | + |
| 268 | +**Parameters**: |
| 269 | + |
| 270 | + * **timeout_ms** The waiting time in milliseconds. |
| 271 | + |
| 272 | + |
| 273 | +**Return**: |
| 274 | + |
| 275 | + * RMW_RET_OK when success. |
| 276 | + * RMW_RET_ERROR If no session is running or the synchronization fails. |
| 277 | + |
| 278 | + |
| 279 | + |
| 280 | + |
| 281 | + |
| 282 | + |
| 283 | +------------------------------- |
0 commit comments