rosidl_runtime_c  master
Generate the rosidl interfaces in C.
u16string_functions.h
Go to the documentation of this file.
1 // Copyright 2015-2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef ROSIDL_RUNTIME_C__U16STRING_FUNCTIONS_H_
16 #define ROSIDL_RUNTIME_C__U16STRING_FUNCTIONS_H_
17 
18 #include <stddef.h>
19 
22 
23 #ifdef __cplusplus
24 extern "C"
25 {
26 #endif
27 
29 /* The contents of rosidl_runtime_c__U16String are initialized to a single null character.
30  * The string initially has size 0 and capacity 1.
31  * Size represents the size of the contents of the string, while capacity represents the overall
32  * storage of the string (counting the null terminator).
33  * All strings must be null-terminated.
34  * The rosidl_runtime_c__U16String structure should be deallocated using the given function
35  * rosidl_runtime_c__U16String__fini() when it is no longer needed.
36  * Calling this function with an already initialized U16 string sequence structure will leak
37  * memory.
38  *
39  * \param[inout] str a pointer to a U16 string structure
40  * \return true if successful, false if the passed string pointer is null
41  * or the memory allocation failed
42  */
44 bool
46 
48 /*
49 * Calling the function with an already deallocated sequence is a no-op.
50 *
51 * \param[inout] str a pointer to a U16 string structure to be finalized
52 */
54 void
56 
58 /*
59  * This function returns `false` if memory cannot be allocated,
60  * if the input uint16_t pointer is null or if the size is higher than SIZE_MAX.
61  * In both cases no error message is set.
62  *
63  * \param[inout] str a pointer to a U16 string structure
64  * \param[in] value points to a sequence of 16 bit chars
65  * \param[in] n size of the value string
66  * \return true if successful, false if the passed string pointer is null
67  * or if the passed value pointer is null or if the size is higher than SIZE_MAX
68  * or if the memory reallocation failed.
69  */
71 bool
73  rosidl_runtime_c__U16String * str, const uint16_t * value, size_t n);
74 
76 /*
77  * This function is identical to rosidl_runtime_c__U16String__assignn() except the type of the
78  * value is c string pointer
79  *
80  * \see rosidl_runtime_c__U16String__assignn()
81  *
82  * \param[inout] str a pointer to a U16 string structure
83  * \param[in] value points to a sequence of 16 bit chars
84  * \param[in] n size of the value string
85  * \return true if successful, false if the passed string pointer is null
86  * or if the passed value pointer is null or if the size is higher than SIZE_MAX
87  * or if the memory reallocation failed.
88  */
90 bool
92  rosidl_runtime_c__U16String * str, const char * value, size_t n);
93 
95 /*
96  * This function is identical to rosidl_runtime_c__U16String__assignn() except the length of the
97  * uint16_t does not have to be given.
98  * rosidl_runtime_c__U16String__len() is being used to determine the length of the passed string.
99  *
100  * \see rosidl_runtime_c__U16String__assignn()
101  *
102  * \param[inout] str a pointer to a rosidl_runtime_c__U16String structure
103  * \param[in] value points to a sequence of 16 bit chars
104  * \return true if successful, false if the passed string pointer is null
105  * or if the passed value pointer is null or if the size is higher than SIZE_MAX
106  * or if the memory reallocation failed.
107  */
109 bool
111  rosidl_runtime_c__U16String * str, const uint16_t * value);
112 
114 /*
115  * This function returns the length of the input value pointer.
116  *
117  * \param[in] value points to a sequence of 16 bit chars for which the first null char is
118  * determined
119  * \return the size of the input value pointer or zero if the pointer is NULL
120  */
122 size_t
123 rosidl_runtime_c__U16String__len(const uint16_t * value);
124 
126 /*
127  * This function resize the input value pointer.
128  *
129  * \param[in] n the new size of the internal buffer
130  * \return true if successful, false if the passed string pointer is null
131  * or if the size is higher than SIZE_MAX or if the memory reallocation failed.
132  */
134 bool
136  rosidl_runtime_c__U16String * str, size_t n);
137 
139 /*
140  * The rosidl_runtime_c__U16String__Sequence is initialized to the size passed to the function.
141  * The U16 string sequence structure should be deallocated using the given
142  * function rosidl_runtime_c__U16String__Sequence__fini() when it is no longer needed.
143  * Calling this function with an already initialized U16 string sequence structure will leak
144  * memory.
145  *
146  * \param[inout] sequence a pointer to a U16 string sequence structure
147  * \param[in] size represents the size of the U16 string
148  * \return true if successful, false if the passed string pointer is null
149  * or the memory allocation failed
150  */
152 bool
154  rosidl_runtime_c__U16String__Sequence * sequence, size_t size);
155 
157 /*
158  * Calling the function with an already deallocated sequence is a no-op.
159  *
160  * \param[inout] sequence a pointer to a U16 string to be finalized
161  */
163 void
165  rosidl_runtime_c__U16String__Sequence * sequence);
166 
168 /*
169  * The U16 string sequence initially has size and capacity equal to the size
170  * argument.
171  * The U16 string sequence structure should be deallocated using the given
172  * function rosidl_runtime_c__U16String__Sequence__destroy() when it is no longer needed.
173  *
174  * \param[in] size of the desired U16 string
175  * \return a U16 string sequence if initialization was successfully, otherwise NULL.
176  */
178 rosidl_runtime_c__U16String__Sequence *
180 
182 /*
183  * Calling the function with an already deallocated sequence is a no-op.
184  *
185  * \param[inout] sequence a pointer to a U16 string sequence to be finalized
186  */
188 void
190  rosidl_runtime_c__U16String__Sequence * sequence);
191 
192 #ifdef __cplusplus
193 }
194 #endif
195 
196 #endif // ROSIDL_RUNTIME_C__U16STRING_FUNCTIONS_H_
rosidl_runtime_c__U16String__Sequence__init
bool rosidl_runtime_c__U16String__Sequence__init(rosidl_runtime_c__U16String__Sequence *sequence, size_t size)
Initialize a U16 string sequence structure.
u16string.h
rosidl_runtime_c__U16String__assignn
bool rosidl_runtime_c__U16String__assignn(rosidl_runtime_c__U16String *str, const uint16_t *value, size_t n)
Assign the uint16_t value of n characters to the rosidl_runtime_c__U16String structure.
rosidl_runtime_c__U16String__init
bool rosidl_runtime_c__U16String__init(rosidl_runtime_c__U16String *str)
Initialize a rosidl_runtime_c__U16String structure.
rosidl_runtime_c__U16String__assign
bool rosidl_runtime_c__U16String__assign(rosidl_runtime_c__U16String *str, const uint16_t *value)
Assign the uint16_t pointer to the rosidl_runtime_c__U16String structure.
rosidl_runtime_c__U16String__resize
bool rosidl_runtime_c__U16String__resize(rosidl_runtime_c__U16String *str, size_t n)
Resize the uint16_t pointer.
rosidl_runtime_c__U16String__fini
void rosidl_runtime_c__U16String__fini(rosidl_runtime_c__U16String *str)
Deallocate the memory of the rosidl_runtime_c__U16String structure.
rosidl_runtime_c__U16String__Sequence__fini
void rosidl_runtime_c__U16String__Sequence__fini(rosidl_runtime_c__U16String__Sequence *sequence)
Deallocate the memory of the string sequence structure.
rosidl_runtime_c__U16String__Sequence__destroy
void rosidl_runtime_c__U16String__Sequence__destroy(rosidl_runtime_c__U16String__Sequence *sequence)
Destroy a U16 string sequence structure.
visibility_control.h
rosidl_runtime_c__U16String__Sequence__create
rosidl_runtime_c__U16String__Sequence * rosidl_runtime_c__U16String__Sequence__create(size_t size)
Create a U16 string sequence structure with a specific size.
rosidl_runtime_c__U16String__len
size_t rosidl_runtime_c__U16String__len(const uint16_t *value)
Get the length of the uint16_t pointer.
rosidl_runtime_c__U16String
An array of 16-bit characters terminated by a null character.
Definition: u16string.h:23
rosidl_runtime_c__U16String__assignn_from_char
bool rosidl_runtime_c__U16String__assignn_from_char(rosidl_runtime_c__U16String *str, const char *value, size_t n)
Assign the c string pointer value of n characters to the rosidl_runtime_c__U16String structure.
ROSIDL_GENERATOR_C_PUBLIC
#define ROSIDL_GENERATOR_C_PUBLIC
Definition: visibility_control.h:48