Skip to content

Commit a0bc146

Browse files
committed
Typos corrections
1 parent 6b2ad44 commit a0bc146

File tree

5 files changed

+12
-12
lines changed

5 files changed

+12
-12
lines changed

rmw_microxrcedds_c/src/callbacks.c

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ void on_topic(
4949
if ((custom_subscription->datareader_id.id == object_id.id) &&
5050
(custom_subscription->datareader_id.type == object_id.type))
5151
{
52-
custom_subscription->micro_buffer_lenght[custom_subscription->history_write_index] = length;
52+
custom_subscription->micro_buffer_length[custom_subscription->history_write_index] = length;
5353
ucdr_deserialize_array_uint8_t(
5454
ub,
5555
custom_subscription->micro_buffer[custom_subscription->history_write_index], length);
@@ -89,7 +89,7 @@ void on_request(
8989
while (service_item != NULL) {
9090
rmw_uxrce_service_t * custom_service = (rmw_uxrce_service_t *)service_item->data;
9191
if (custom_service->request_id == request_id) {
92-
custom_service->micro_buffer_lenght[custom_service->history_write_index] = length;
92+
custom_service->micro_buffer_length[custom_service->history_write_index] = length;
9393
ucdr_deserialize_array_uint8_t(
9494
ub,
9595
custom_service->micro_buffer[custom_service->history_write_index], length);
@@ -132,7 +132,7 @@ void on_reply(
132132
while (client_item != NULL) {
133133
rmw_uxrce_client_t * custom_client = (rmw_uxrce_client_t *)client_item->data;
134134
if (custom_client->request_id == request_id) {
135-
custom_client->micro_buffer_lenght[custom_client->history_write_index] = length;
135+
custom_client->micro_buffer_length[custom_client->history_write_index] = length;
136136
ucdr_deserialize_array_uint8_t(
137137
ub,
138138
custom_client->micro_buffer[custom_client->history_write_index], length);

rmw_microxrcedds_c/src/rmw_request.c

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ rmw_take_request(
110110
ucdrBuffer temp_buffer;
111111
ucdr_init_buffer(
112112
&temp_buffer, custom_service->micro_buffer[custom_service->history_read_index],
113-
custom_service->micro_buffer_lenght[custom_service->history_read_index]);
113+
custom_service->micro_buffer_length[custom_service->history_read_index]);
114114

115115

116116
bool deserialize_rv = functions->cdr_deserialize(&temp_buffer, ros_request);

rmw_microxrcedds_c/src/rmw_response.c

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,13 +53,13 @@ rmw_send_response(
5353
uint32_t topic_size = functions->get_serialized_size(ros_response);
5454

5555
ucdrBuffer reply_ub;
56-
ucdr_init_buffer(&reply_ub, custom_service->replay_buffer, sizeof(custom_service->replay_buffer));
56+
ucdr_init_buffer(&reply_ub, custom_service->reply_buffer, sizeof(custom_service->reply_buffer));
5757

5858
functions->cdr_serialize(ros_response, &reply_ub);
5959

6060
uxr_buffer_reply(
6161
&custom_node->context->session, custom_service->stream_id,
62-
custom_service->service_id, &sample_id, custom_service->replay_buffer, topic_size);
62+
custom_service->service_id, &sample_id, custom_service->reply_buffer, topic_size);
6363

6464
return RMW_RET_OK;
6565
}
@@ -100,7 +100,7 @@ rmw_take_response(
100100
ucdrBuffer temp_buffer;
101101
ucdr_init_buffer(
102102
&temp_buffer, custom_client->micro_buffer[custom_client->history_read_index],
103-
custom_client->micro_buffer_lenght[custom_client->history_read_index]);
103+
custom_client->micro_buffer_length[custom_client->history_read_index]);
104104

105105
bool deserialize_rv = functions->cdr_deserialize(
106106
&temp_buffer,

rmw_microxrcedds_c/src/rmw_take.c

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ rmw_take_with_info(
5858
ucdrBuffer temp_buffer;
5959
ucdr_init_buffer(
6060
&temp_buffer, custom_subscription->micro_buffer[custom_subscription->history_read_index],
61-
custom_subscription->micro_buffer_lenght[custom_subscription->history_read_index]);
61+
custom_subscription->micro_buffer_length[custom_subscription->history_read_index]);
6262

6363
bool deserialize_rv = custom_subscription->type_support_callbacks->cdr_deserialize(
6464
&temp_buffer,

rmw_microxrcedds_c/src/types.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -115,15 +115,15 @@ typedef struct rmw_uxrce_service_t
115115

116116
SampleIdentity sample_id[RMW_UXRCE_MAX_HISTORY];
117117
uint8_t micro_buffer[RMW_UXRCE_MAX_HISTORY][RMW_UXRCE_MAX_BUFFER_SIZE];
118-
size_t micro_buffer_lenght[RMW_UXRCE_MAX_HISTORY];
118+
size_t micro_buffer_length[RMW_UXRCE_MAX_HISTORY];
119119

120120
uint8_t history_write_index;
121121
uint8_t history_read_index;
122122
bool micro_buffer_in_use;
123123

124124
uxrStreamId stream_id;
125125

126-
uint8_t replay_buffer[RMW_UXRCE_MAX_TRANSPORT_MTU];
126+
uint8_t reply_buffer[RMW_UXRCE_MAX_TRANSPORT_MTU];
127127

128128
struct rmw_uxrce_node_t * owner_node;
129129
} rmw_uxrce_service_t;
@@ -139,7 +139,7 @@ typedef struct rmw_uxrce_client_t
139139

140140
int64_t reply_id[RMW_UXRCE_MAX_HISTORY];
141141
uint8_t micro_buffer[RMW_UXRCE_MAX_HISTORY][RMW_UXRCE_MAX_BUFFER_SIZE];
142-
size_t micro_buffer_lenght[RMW_UXRCE_MAX_HISTORY];
142+
size_t micro_buffer_length[RMW_UXRCE_MAX_HISTORY];
143143

144144
uint8_t history_write_index;
145145
uint8_t history_read_index;
@@ -162,7 +162,7 @@ typedef struct rmw_uxrce_subscription_t
162162
const message_type_support_callbacks_t * type_support_callbacks;
163163

164164
uint8_t micro_buffer[RMW_UXRCE_MAX_HISTORY][RMW_UXRCE_MAX_BUFFER_SIZE];
165-
size_t micro_buffer_lenght[RMW_UXRCE_MAX_HISTORY];
165+
size_t micro_buffer_length[RMW_UXRCE_MAX_HISTORY];
166166

167167
uint8_t history_write_index;
168168
uint8_t history_read_index;

0 commit comments

Comments
 (0)