9 NormalDisplay::NormalDisplay():skip_rate_(1),scale_(0.3),alpha_(1.0)
13 "Skip the display normals for speed up. Around 1% is recommended",
20 "set the scale of arrow",
27 "set the alpha of arrow",
34 "Rendering mode to use, in order of computational complexity.",
42 "Color to assign to every point.",
this);
59 float h =
value * 5.0f + 1.0f;
62 if ( !(i&1) )
f = 1 -
f;
64 if (i <= 1) rf = n, gf = 0, bf = 1;
65 else if (i == 2) rf = 0, gf = n, bf = 1;
66 else if (i == 3) rf = 0, gf = 1, bf = n;
67 else if (i == 4) rf = n, gf = 1, bf = 0;
68 else if (i >= 5) rf = 1, gf = n, bf = 0;
150 if (xi == -1 || yi == -1 || zi == -1)
156 const uint32_t xoff =
msg->fields[xi].offset;
157 const uint32_t yoff =
msg->fields[yi].offset;
158 const uint32_t zoff =
msg->fields[zi].offset;
166 if (normal_xi == -1 || normal_yi == -1 || normal_zi == -1 || curvature_i == -1)
168 ROS_ERROR(
"doesn't have normal_x, normal_y, normal_z, curvature");
172 const uint32_t normal_xoff =
msg->fields[normal_xi].offset;
173 const uint32_t normal_yoff =
msg->fields[normal_yi].offset;
174 const uint32_t normal_zoff =
msg->fields[normal_zi].offset;
175 const uint32_t curvature_off =
msg->fields[curvature_i].offset;
179 uint32_t rgbaoff = -1;
181 rgbaoff =
msg->fields[rgbai].offset;
184 const uint32_t point_step =
msg->point_step;
185 const size_t point_count =
msg->width *
msg->height;
187 if (point_count == 0)
189 ROS_ERROR(
"doesn't have point_count > 0");
193 Ogre::Quaternion orientation;
194 Ogre::Vector3 position;
197 position, orientation ))
199 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
205 skip_time = std::max(skip_time, 1);
206 skip_time = std::min(skip_time,
int(point_count / 2));
207 visuals_.rset_capacity(
int(point_count/skip_time));
208 const uint8_t* ptr = &
msg->data.front();
211 static float prev_max_curvature = 0.0;
212 static float prev_min_curvature = 1.0;
213 float max_curvature = 0.0;
214 float min_curvature = 1.0;
218 for (
size_t i = 0; i < point_count; ++i)
220 if(i % skip_time != 0){
224 float x = *
reinterpret_cast<const float*
>(ptr + xoff);
225 float y = *
reinterpret_cast<const float*
>(ptr + yoff);
226 float z = *
reinterpret_cast<const float*
>(ptr + zoff);
227 float normal_x = *
reinterpret_cast<const float*
>(ptr + normal_xoff);
228 float normal_y = *
reinterpret_cast<const float*
>(ptr + normal_yoff);
229 float normal_z = *
reinterpret_cast<const float*
>(ptr + normal_zoff);
230 float curvature = *
reinterpret_cast<const float*
>(ptr + curvature_off);
235 #if ROS_VERSION_MINIMUM(1,12,0)
236 std::shared_ptr<NormalVisual> visual;
245 visual->setValues(
x,
y,
z, normal_x, normal_y, normal_z );
246 visual->setFramePosition( position );
247 visual->setFrameOrientation( orientation );
248 visual->setScale(
scale_ );
251 Ogre::Vector3 dir_vec(normal_x, normal_y, normal_z);
257 b = *
reinterpret_cast<const uint8_t*
>(ptr + rgbaoff);
258 g = *
reinterpret_cast<const uint8_t*
>(ptr + rgbaoff + 1*
sizeof(uint8_t));
259 r = *
reinterpret_cast<const uint8_t*
>(ptr + rgbaoff + 2*
sizeof(uint8_t));
261 visual->setColor(
r/256.0,
g/256.0,
b/256.0,
alpha_ );
265 visual->setColor(color.redF(), color.greenF(), color.blueF(),
alpha_);
268 visual->setColor( dir_vec.dotProduct(Ogre::Vector3(-1,0,0)), dir_vec.dotProduct(Ogre::Vector3(0,1,0)), dir_vec.dotProduct(Ogre::Vector3(0,0,-1)),
alpha_ );
272 float prev_diff = prev_max_curvature - prev_min_curvature;
273 float value = 1 - (curvature - prev_min_curvature)/prev_diff;
276 visual->setColor( rf, gf, bf,
alpha_);
278 float value = curvature/(prev_max_curvature - prev_min_curvature);
282 float rf = max_color.r *
value + min_color.r * ( 1 -
value );
283 float gf = max_color.g *
value + min_color.g * ( 1 -
value );
284 float bf = max_color.b *
value + min_color.b * ( 1 -
value );
285 visual->setColor( rf, gf, bf,
alpha_);
287 max_curvature = std::max(max_curvature, curvature);
288 min_curvature = std::min(min_curvature, curvature);
297 prev_min_curvature = min_curvature;
298 prev_max_curvature = max_curvature;