Skip to content

Commit 54c7855

Browse files
micro-ROS foxy Library auto-update 25-02-2021 06:20 (#141)
Co-authored-by: pablogs9 <[email protected]>
1 parent d389a3a commit 54c7855

File tree

5 files changed

+9
-13
lines changed

5 files changed

+9
-13
lines changed

built_packages

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,10 @@ https://github.com/micro-ROS/rcutils 6f0e5d7d3da4ab1c1744dfa8452fdd5e01e912d9
2525
https://gitlab.com/micro-ROS/ros_tracing/ros2_tracing d11b87737245b8456bbada44dfa7b1d670b1c4d0
2626
https://github.com/micro-ROS/rosidl_typesupport.git 9c0b5fde7d7e148685bb9e1692dcc8600cdeb96a
2727
https://github.com/micro-ROS/micro_ros_msgs.git 9a3968d4694f516ded8bdbfe23e2a487477bb8b4
28-
https://github.com/micro-ROS/rmw-microxrcedds.git 4c588fcfc0baff3fd0ea701ce1f9e97c7ad917f1
28+
https://github.com/micro-ROS/rmw-microxrcedds.git a8f2a227e35c7ae42796a12505f9af6071e7edf1
2929
https://github.com/micro-ROS/rcl 8eddc13db38bdecdd3089b8c96d13f0df3f5b35d
3030
https://github.com/micro-ROS/rosidl_typesupport_microxrcedds.git f917106cd82ad17853e48ea2641b50563cd473dd
3131
https://github.com/micro-ROS/rclc 1bfad129443d65b8dfe74e098cb59d9a6fbaf46f
3232
https://github.com/ros-controls/control_msgs 653b646ba34d2166149cc02269bac0f48beb72b0
33-
https://github.com/eProsima/Micro-XRCE-DDS-Client.git 0d47a98ae9854d178326184f38663f419c493a61
33+
https://github.com/eProsima/Micro-XRCE-DDS-Client.git 545e0da82657349e4f071846d937c47494f75572
3434
https://github.com/eProsima/Micro-CDR.git c95c40f427e421bcdf259f52501414dfbc2b2b22

src/rmw_microxrcedds_c/config.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#define RMW_UXRCE_MAX_TRANSPORT_MTU UXR_CONFIG_SERIAL_TRANSPORT_MTU
2222
#define RMW_UXRCE_DEFAULT_SERIAL_DEVICE ""
2323
#elif defined(RMW_UXRCE_TRANSPORT_CUSTOM)
24-
#define RMW_UXRCE_MAX_TRANSPORT_MTU UCLIENT_CUSTOM_TRANSPORT_MTU
24+
#define RMW_UXRCE_MAX_TRANSPORT_MTU UXR_CONFIG_CUSTOM_TRANSPORT_MTU
2525
#endif
2626

2727
/* #undef RMW_UXRCE_STREAM_HISTORY_INPUT */

src/uxr/client/config.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@
5656
#define UXR_CONFIG_SERIAL_TRANSPORT_MTU 512
5757
#endif
5858
#ifdef UCLIENT_PROFILE_CUSTOM_TRANSPORT
59-
#define UCLIENT_CUSTOM_TRANSPORT_MTU 512
59+
#define UXR_CONFIG_CUSTOM_TRANSPORT_MTU 512
6060
#endif
6161

6262
#endif // _UXR_CLIENT_CONFIG_H_

src/uxr/client/core/session/session.h

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -235,8 +235,7 @@ UXRDLLAPI bool uxr_delete_session_retries(uxrSession* session, size_t retries);
235235

236236
/**
237237
* @brief Creates and initializes an output best-effort stream.
238-
* The maximum number of output best-effort streams is set by the `CONFIG_MAX_OUTPUT_BEST_EFFORT_STREAMS`
239-
* variable at `client.config` file.
238+
* The maximum number of output best-effort streams is set by the `CONFIG_MAX_OUTPUT_BEST_EFFORT_STREAMS`.
240239
* @param session A uxrSession structure previously initialized.
241240
* @param buffer The memory block where the messages will be written.
242241
* @param size The buffer size.
@@ -249,8 +248,7 @@ UXRDLLAPI uxrStreamId uxr_create_output_best_effort_stream(
249248

250249
/**
251250
* @brief Creates and initializes an output reliable stream.
252-
* The maximum number of output reliable streams is set by the `CONFIG_MAX_OUTPUT_RELIABLE_STREAMS`
253-
* variable at `client.config` file.
251+
* The maximum number of output reliable streams is set by the `CONFIG_MAX_OUTPUT_RELIABLE_STREAMS`.
254252
* @param session A uxrSession structure previously initialized.
255253
* @param buffer The memory block where the messages will be written.
256254
* @param size The buffer size.
@@ -267,17 +265,15 @@ UXRDLLAPI uxrStreamId uxr_create_output_reliable_stream(
267265

268266
/**
269267
* @brief Creates and initializes an input best-effort stream.
270-
* The maximum number of input best-effort streams is set by the `CONFIG_MAX_INPUT_BEST_EFFORT_STREAMS`
271-
* variable at `client.config` file.
268+
* The maximum number of input best-effort streams is set by the `CONFIG_MAX_INPUT_BEST_EFFORT_STREAMS`.
272269
* @param session A uxrSession structure previously initialized.
273270
* @return A uxrStreamId which could by used for managing the stream.
274271
*/
275272
UXRDLLAPI uxrStreamId uxr_create_input_best_effort_stream(uxrSession* session);
276273

277274
/**
278275
* @brief Creates and initializes an input reliable stream.
279-
* The maximum number of input reliable streams is set by the `CONFIG_MAX_INPUT_RELIABLE_STREAMS`
280-
* variable at `client.config` file.
276+
* The maximum number of input reliable streams is set by the `CONFIG_MAX_INPUT_RELIABLE_STREAMS`.
281277
* @param session A uxrSession structure previously initialized.
282278
* @param buffer The memory block where the messages will be written.
283279
* @param size The buffer size.

src/uxr/client/profile/transport/custom/custom_transport.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ typedef size_t (*read_custom_func)(struct uxrCustomTransport*, uint8_t*, size_t,
3434

3535
typedef struct uxrCustomTransport
3636
{
37-
uint8_t buffer[UCLIENT_CUSTOM_TRANSPORT_MTU];
37+
uint8_t buffer[UXR_CONFIG_CUSTOM_TRANSPORT_MTU];
3838
bool framing;
3939
uxrFramingIO framing_io;
4040
open_custom_func open;

0 commit comments

Comments
 (0)