Skip to content

Commit fb4964a

Browse files
committed
Uncrustify.
Signed-off-by: Michael Carroll <[email protected]>
1 parent 0181285 commit fb4964a

File tree

1 file changed

+84
-65
lines changed

1 file changed

+84
-65
lines changed

sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp

Lines changed: 84 additions & 65 deletions
Original file line numberDiff line numberDiff line change
@@ -46,86 +46,95 @@
4646
*/
4747
namespace sensor_msgs
4848
{
49-
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
50-
/** \brief Get the index of a specified field (i.e., dimension/channel)
51-
* \param points the the point cloud message
52-
* \param field_name the string defining the field name
53-
*/
54-
static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
49+
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
50+
/** \brief Get the index of a specified field (i.e., dimension/channel)
51+
* \param points the the point cloud message
52+
* \param field_name the string defining the field name
53+
*/
54+
static inline int getPointCloud2FieldIndex(
55+
const sensor_msgs::PointCloud2 & cloud,
56+
const std::string & field_name)
5557
{
5658
// Get the index we need
57-
for (size_t d = 0; d < cloud.fields.size (); ++d)
58-
if (cloud.fields[d].name == field_name)
59-
return (d);
60-
return (-1);
59+
for (size_t d = 0; d < cloud.fields.size(); ++d) {
60+
if (cloud.fields[d].name == field_name) {
61+
return d;
62+
}
63+
}
64+
return -1;
6165
}
6266

63-
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
64-
/** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
65-
* \param input the message in the sensor_msgs::PointCloud format
66-
* \param output the resultant message in the sensor_msgs::PointCloud2 format
67-
*/
68-
static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
67+
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
68+
/** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
69+
* \param input the message in the sensor_msgs::PointCloud format
70+
* \param output the resultant message in the sensor_msgs::PointCloud2 format
71+
*/
72+
static inline bool convertPointCloudToPointCloud2(
73+
const sensor_msgs::PointCloud & input,
74+
sensor_msgs::PointCloud2 & output)
6975
{
7076
output.header = input.header;
71-
output.width = input.points.size ();
77+
output.width = input.points.size();
7278
output.height = 1;
73-
output.fields.resize (3 + input.channels.size ());
79+
output.fields.resize(3 + input.channels.size());
7480
// Convert x/y/z to fields
7581
output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z";
7682
int offset = 0;
7783
// All offsets are *4, as all field data types are float32
78-
for (size_t d = 0; d < output.fields.size (); ++d, offset += 4)
79-
{
84+
for (size_t d = 0; d < output.fields.size(); ++d, offset += 4) {
8085
output.fields[d].offset = offset;
8186
output.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
82-
output.fields[d].count = 1;
87+
output.fields[d].count = 1;
8388
}
8489
output.point_step = offset;
85-
output.row_step = output.point_step * output.width;
90+
output.row_step = output.point_step * output.width;
8691
// Convert the remaining of the channels to fields
87-
for (size_t d = 0; d < input.channels.size (); ++d)
92+
for (size_t d = 0; d < input.channels.size(); ++d) {
8893
output.fields[3 + d].name = input.channels[d].name;
89-
output.data.resize (input.points.size () * output.point_step);
94+
}
95+
output.data.resize(input.points.size() * output.point_step);
9096
output.is_bigendian = false; // @todo ?
91-
output.is_dense = false;
97+
output.is_dense = false;
9298

9399
// Copy the data points
94-
for (size_t cp = 0; cp < input.points.size (); ++cp)
95-
{
96-
memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float));
97-
memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float));
98-
memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float));
99-
for (size_t d = 0; d < input.channels.size (); ++d)
100-
{
101-
if (input.channels[d].values.size() == input.points.size())
102-
{
103-
memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float));
100+
for (size_t cp = 0; cp < input.points.size(); ++cp) {
101+
memcpy(&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x,
102+
sizeof(float));
103+
memcpy(&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y,
104+
sizeof(float));
105+
memcpy(&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z,
106+
sizeof(float));
107+
for (size_t d = 0; d < input.channels.size(); ++d) {
108+
if (input.channels[d].values.size() == input.points.size()) {
109+
memcpy(&output.data[cp * output.point_step + output.fields[3 + d].offset],
110+
&input.channels[d].values[cp], sizeof(float));
104111
}
105112
}
106113
}
107-
return (true);
114+
return true;
108115
}
109116

110-
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
111-
/** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
112-
* \param input the message in the sensor_msgs::PointCloud2 format
113-
* \param output the resultant message in the sensor_msgs::PointCloud format
114-
*/
115-
static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
117+
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
118+
/** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
119+
* \param input the message in the sensor_msgs::PointCloud2 format
120+
* \param output the resultant message in the sensor_msgs::PointCloud format
121+
*/
122+
static inline bool convertPointCloud2ToPointCloud(
123+
const sensor_msgs::PointCloud2 & input,
124+
sensor_msgs::PointCloud & output)
116125
{
117126

118127
output.header = input.header;
119-
output.points.resize (input.width * input.height);
120-
output.channels.resize (input.fields.size () - 3);
128+
output.points.resize(input.width * input.height);
129+
output.channels.resize(input.fields.size() - 3);
121130
// Get the x/y/z field offsets
122-
int x_idx = getPointCloud2FieldIndex (input, "x");
123-
int y_idx = getPointCloud2FieldIndex (input, "y");
124-
int z_idx = getPointCloud2FieldIndex (input, "z");
125-
if (x_idx == -1 || y_idx == -1 || z_idx == -1)
126-
{
127-
std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl;
128-
return (false);
131+
int x_idx = getPointCloud2FieldIndex(input, "x");
132+
int y_idx = getPointCloud2FieldIndex(input, "y");
133+
int z_idx = getPointCloud2FieldIndex(input, "z");
134+
if (x_idx == -1 || y_idx == -1 || z_idx == -1) {
135+
std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" <<
136+
std::endl;
137+
return false;
129138
}
130139
int x_offset = input.fields[x_idx].offset;
131140
int y_offset = input.fields[y_idx].offset;
@@ -136,32 +145,42 @@ static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud
136145

137146
// Convert the fields to channels
138147
int cur_c = 0;
139-
for (size_t d = 0; d < input.fields.size (); ++d)
140-
{
141-
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
148+
for (size_t d = 0; d < input.fields.size(); ++d) {
149+
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset ||
150+
(int)input.fields[d].offset == z_offset)
151+
{
142152
continue;
153+
}
143154
output.channels[cur_c].name = input.fields[d].name;
144-
output.channels[cur_c].values.resize (output.points.size ());
155+
output.channels[cur_c].values.resize(output.points.size());
145156
cur_c++;
146157
}
147158

148159
// Copy the data points
149-
for (size_t cp = 0; cp < output.points.size (); ++cp)
150-
{
160+
for (size_t cp = 0; cp < output.points.size(); ++cp) {
151161
// Copy x/y/z
152-
output.points[cp].x = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + x_offset], x_datatype);
153-
output.points[cp].y = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + y_offset], y_datatype);
154-
output.points[cp].z = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + z_offset], z_datatype);
162+
output.points[cp].x =
163+
sensor_msgs::readPointCloud2BufferValue<float>(
164+
&input.data[cp * input.point_step + x_offset], x_datatype);
165+
output.points[cp].y =
166+
sensor_msgs::readPointCloud2BufferValue<float>(
167+
&input.data[cp * input.point_step + y_offset], y_datatype);
168+
output.points[cp].z =
169+
sensor_msgs::readPointCloud2BufferValue<float>(
170+
&input.data[cp * input.point_step + z_offset], z_datatype);
155171
// Copy the rest of the data
156172
int cur_c = 0;
157-
for (size_t d = 0; d < input.fields.size (); ++d)
158-
{
159-
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
173+
for (size_t d = 0; d < input.fields.size(); ++d) {
174+
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset ||
175+
(int)input.fields[d].offset == z_offset)
176+
{
160177
continue;
161-
output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype);
178+
}
179+
output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue<float>(
180+
&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype);
162181
}
163182
}
164-
return (true);
183+
return true;
165184
}
166185
} // namespace sensor_msgs
167186

0 commit comments

Comments
 (0)