/
map_display.cpp
536 lines (448 loc) · 15.8 KB
/
map_display.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
/*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <boost/bind.hpp>
#include <OGRE/OgreManualObject.h>
#include <OGRE/OgreMaterialManager.h>
#include <OGRE/OgreSceneManager.h>
#include <OGRE/OgreSceneNode.h>
#include <OGRE/OgreTextureManager.h>
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include "rviz/frame_manager.h"
#include "rviz/ogre_helpers/grid.h"
#include "rviz/properties/float_property.h"
#include "rviz/properties/int_property.h"
#include "rviz/properties/property.h"
#include "rviz/properties/quaternion_property.h"
#include "rviz/properties/ros_topic_property.h"
#include "rviz/properties/vector_property.h"
#include "rviz/validate_floats.h"
#include "rviz/display_context.h"
#include "map_display.h"
namespace rviz
{
MapDisplay::MapDisplay()
: Display()
, manual_object_( NULL )
, material_( 0 )
, loaded_( false )
, resolution_( 0.0f )
, width_( 0 )
, height_( 0 )
, position_(Ogre::Vector3::ZERO)
, orientation_(Ogre::Quaternion::IDENTITY)
, new_map_(false)
{
topic_property_ = new RosTopicProperty( "Topic", "",
QString::fromStdString( ros::message_traits::datatype<nav_msgs::OccupancyGrid>() ),
"nav_msgs::OccupancyGrid topic to subscribe to.",
this, SLOT( updateTopic() ));
alpha_property_ = new FloatProperty( "Alpha", 0.7,
"Amount of transparency to apply to the map.",
this, SLOT( updateAlpha() ));
alpha_property_->setMin( 0 );
alpha_property_->setMax( 1 );
draw_under_property_ = new Property( "Draw Behind", false,
"Rendering option, controls whether or not the map is always"
" drawn behind everything else.",
this, SLOT( updateDrawUnder() ));
resolution_property_ = new FloatProperty( "Resolution", 0,
"Resolution of the map. (not editable)", this );
resolution_property_->setReadOnly( true );
width_property_ = new IntProperty( "Width", 0,
"Width of the map, in meters. (not editable)", this );
width_property_->setReadOnly( true );
height_property_ = new IntProperty( "Height", 0,
"Height of the map, in meters. (not editable)", this );
height_property_->setReadOnly( true );
position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO,
"Position of the bottom left corner of the map, in meters. (not editable)",
this );
position_property_->setReadOnly( true );
orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY,
"Orientation of the map. (not editable)",
this );
orientation_property_->setReadOnly( true );
}
MapDisplay::~MapDisplay()
{
unsubscribe();
clear();
}
void MapDisplay::onInitialize()
{
static int count = 0;
std::stringstream ss;
ss << "MapObjectMaterial" << count++;
material_ = Ogre::MaterialManager::getSingleton().create( ss.str(),
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
material_->setReceiveShadows(false);
material_->getTechnique(0)->setLightingEnabled(false);
material_->setDepthBias( -16.0f, 0.0f );
material_->setCullingMode( Ogre::CULL_NONE );
material_->setDepthWriteEnabled(false);
updateAlpha();
}
void MapDisplay::onEnable()
{
subscribe();
}
void MapDisplay::onDisable()
{
unsubscribe();
clear();
}
void MapDisplay::subscribe()
{
if ( !isEnabled() )
{
return;
}
if( !topic_property_->getTopic().isEmpty() )
{
try
{
map_sub_ = update_nh_.subscribe( topic_property_->getTopicStd(), 1, &MapDisplay::incomingMap, this );
setStatus( StatusProperty::Ok, "Topic", "OK" );
}
catch( ros::Exception& e )
{
setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
}
}
}
void MapDisplay::unsubscribe()
{
map_sub_.shutdown();
}
void MapDisplay::updateAlpha()
{
float alpha = alpha_property_->getFloat();
Ogre::Pass* pass = material_->getTechnique( 0 )->getPass( 0 );
Ogre::TextureUnitState* tex_unit = NULL;
if( pass->getNumTextureUnitStates() > 0 )
{
tex_unit = pass->getTextureUnitState( 0 );
}
else
{
tex_unit = pass->createTextureUnitState();
}
tex_unit->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
if( alpha < 0.9998 )
{
material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
material_->setDepthWriteEnabled( false );
}
else
{
material_->setSceneBlending( Ogre::SBT_REPLACE );
material_->setDepthWriteEnabled( !draw_under_property_->getValue().toBool() );
}
}
void MapDisplay::updateDrawUnder()
{
bool draw_under = draw_under_property_->getValue().toBool();
if( alpha_property_->getFloat() >= 0.9998 )
{
material_->setDepthWriteEnabled( !draw_under );
}
if( manual_object_ )
{
if( draw_under )
{
manual_object_->setRenderQueueGroup( Ogre::RENDER_QUEUE_4 );
}
else
{
manual_object_->setRenderQueueGroup( Ogre::RENDER_QUEUE_MAIN );
}
}
}
void MapDisplay::updateTopic()
{
unsubscribe();
subscribe();
clear();
}
void MapDisplay::clear()
{
setStatus( StatusProperty::Warn, "Message", "No map received" );
if( !loaded_ )
{
return;
}
scene_manager_->destroyManualObject( manual_object_ );
manual_object_ = NULL;
std::string tex_name = texture_->getName();
texture_.setNull();
Ogre::TextureManager::getSingleton().unload( tex_name );
loaded_ = false;
}
bool validateFloats(const nav_msgs::OccupancyGrid& msg)
{
bool valid = true;
valid = valid && validateFloats( msg.info.resolution );
valid = valid && validateFloats( msg.info.origin );
return valid;
}
void MapDisplay::update( float wall_dt, float ros_dt )
{
{
boost::mutex::scoped_lock lock(mutex_);
current_map_ = updated_map_;
}
if (!current_map_ || !new_map_)
{
return;
}
if (current_map_->data.empty())
{
return;
}
new_map_ = false;
if( !validateFloats( *current_map_ ))
{
setStatus( StatusProperty::Error, "Map", "Message contained invalid floating point values (nans or infs)" );
return;
}
if( current_map_->info.width * current_map_->info.height == 0 )
{
std::stringstream ss;
ss << "Map is zero-sized (" << current_map_->info.width << "x" << current_map_->info.height << ")";
setStatus( StatusProperty::Error, "Map", QString::fromStdString( ss.str() ));
return;
}
clear();
setStatus( StatusProperty::Ok, "Message", "Map received" );
ROS_DEBUG( "Received a %d X %d map @ %.3f m/pix\n",
current_map_->info.width,
current_map_->info.height,
current_map_->info.resolution );
float resolution = current_map_->info.resolution;
int width = current_map_->info.width;
int height = current_map_->info.height;
Ogre::Vector3 position( current_map_->info.origin.position.x,
current_map_->info.origin.position.y,
current_map_->info.origin.position.z );
Ogre::Quaternion orientation( current_map_->info.origin.orientation.w,
current_map_->info.origin.orientation.x,
current_map_->info.origin.orientation.y,
current_map_->info.origin.orientation.z );
frame_ = current_map_->header.frame_id;
if (frame_.empty())
{
frame_ = "/map";
}
// Expand it to be RGB data
unsigned int pixels_size = width * height;
unsigned char* pixels = new unsigned char[pixels_size];
memset(pixels, 255, pixels_size);
bool map_status_set = false;
unsigned int num_pixels_to_copy = pixels_size;
if( pixels_size != current_map_->data.size() )
{
std::stringstream ss;
ss << "Data size doesn't match width*height: width = " << width
<< ", height = " << height << ", data size = " << current_map_->data.size();
setStatus( StatusProperty::Error, "Map", QString::fromStdString( ss.str() ));
map_status_set = true;
// Keep going, but don't read past the end of the data.
if( current_map_->data.size() < pixels_size )
{
num_pixels_to_copy = current_map_->data.size();
}
}
// TODO: a fragment shader could do this on the video card, and
// would allow a non-grayscale color to mark the out-of-range
// values.
for( unsigned int pixel_index = 0; pixel_index < num_pixels_to_copy; pixel_index++ )
{
unsigned char val;
int8_t data = current_map_->data[ pixel_index ];
if( data > 100 )
val = 127;
else if( data < 0 )
val = 127;
else
val = int8_t((int(100 - data) * 255) / 100);
pixels[ pixel_index ] = val;
}
Ogre::DataStreamPtr pixel_stream;
pixel_stream.bind( new Ogre::MemoryDataStream( pixels, pixels_size ));
static int tex_count = 0;
std::stringstream ss;
ss << "MapTexture" << tex_count++;
try
{
texture_ = Ogre::TextureManager::getSingleton().loadRawData( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
pixel_stream, width, height, Ogre::PF_L8, Ogre::TEX_TYPE_2D,
0);
if( !map_status_set )
{
setStatus( StatusProperty::Ok, "Map", "Map OK" );
}
}
catch(Ogre::RenderingAPIException&)
{
Ogre::Image image;
pixel_stream->seek(0);
float fwidth = width;
float fheight = height;
if( width > height )
{
float aspect = fheight / fwidth;
fwidth = 2048;
fheight = fwidth * aspect;
}
else
{
float aspect = fwidth / fheight;
fheight = 2048;
fwidth = fheight * aspect;
}
{
std::stringstream ss;
ss << "Map is larger than your graphics card supports. Downsampled from [" << width << "x" << height << "] to [" << fwidth << "x" << fheight << "]";
setStatus(StatusProperty::Ok, "Map", QString::fromStdString( ss.str() ));
}
ROS_WARN("Failed to create full-size map texture, likely because your graphics card does not support textures of size > 2048. Downsampling to [%d x %d]...", (int)fwidth, (int)fheight);
//ROS_INFO("Stream size [%d], width [%f], height [%f], w * h [%f]", pixel_stream->size(), width, height, width * height);
image.loadRawData(pixel_stream, width, height, Ogre::PF_L8);
image.resize(fwidth, fheight, Ogre::Image::FILTER_NEAREST);
ss << "Downsampled";
texture_ = Ogre::TextureManager::getSingleton().loadImage(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
}
delete [] pixels;
Ogre::Pass* pass = material_->getTechnique(0)->getPass(0);
Ogre::TextureUnitState* tex_unit = NULL;
if (pass->getNumTextureUnitStates() > 0)
{
tex_unit = pass->getTextureUnitState(0);
}
else
{
tex_unit = pass->createTextureUnitState();
}
tex_unit->setTextureName(texture_->getName());
tex_unit->setTextureFiltering( Ogre::TFO_NONE );
static int map_count = 0;
std::stringstream ss2;
ss2 << "MapObject" << map_count++;
manual_object_ = scene_manager_->createManualObject( ss2.str() );
scene_node_->attachObject( manual_object_ );
manual_object_->begin(material_->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
{
// First triangle
{
// Bottom left
manual_object_->position( 0.0f, 0.0f, 0.0f );
manual_object_->textureCoord(0.0f, 0.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
// Top right
manual_object_->position( resolution*width, resolution*height, 0.0f );
manual_object_->textureCoord(1.0f, 1.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
// Top left
manual_object_->position( 0.0f, resolution*height, 0.0f );
manual_object_->textureCoord(0.0f, 1.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
}
// Second triangle
{
// Bottom left
manual_object_->position( 0.0f, 0.0f, 0.0f );
manual_object_->textureCoord(0.0f, 0.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
// Bottom right
manual_object_->position( resolution*width, 0.0f, 0.0f );
manual_object_->textureCoord(1.0f, 0.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
// Top right
manual_object_->position( resolution*width, resolution*height, 0.0f );
manual_object_->textureCoord(1.0f, 1.0f);
manual_object_->normal( 0.0f, 0.0f, 1.0f );
}
}
manual_object_->end();
if( draw_under_property_->getValue().toBool() )
{
manual_object_->setRenderQueueGroup(Ogre::RENDER_QUEUE_4);
}
resolution_property_->setValue( resolution );
width_property_->setValue( width );
height_property_->setValue( height );
position_property_->setVector( position );
orientation_property_->setQuaternion( orientation );
transformMap();
loaded_ = true;
context_->queueRender();
}
void MapDisplay::incomingMap(const nav_msgs::OccupancyGrid::ConstPtr& msg)
{
updated_map_ = msg;
boost::mutex::scoped_lock lock(mutex_);
new_map_ = true;
}
void MapDisplay::transformMap()
{
if (!current_map_)
{
return;
}
Ogre::Vector3 position;
Ogre::Quaternion orientation;
if (!context_->getFrameManager()->transform(frame_, ros::Time(), current_map_->info.origin, position, orientation))
{
ROS_DEBUG( "Error transforming map '%s' from frame '%s' to frame '%s'",
qPrintable( getName() ), frame_.c_str(), qPrintable( fixed_frame_ ));
setStatus( StatusProperty::Error, "Transform",
"No transform from [" + QString::fromStdString( frame_ ) + "] to [" + fixed_frame_ + "]" );
}
else
{
setStatus(StatusProperty::Ok, "Transform", "Transform OK");
}
scene_node_->setPosition( position );
scene_node_->setOrientation( orientation );
}
void MapDisplay::fixedFrameChanged()
{
transformMap();
}
void MapDisplay::reset()
{
Display::reset();
clear();
// Force resubscription so that the map will be re-sent
updateTopic();
}
} // namespace rviz
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS( rviz::MapDisplay, rviz::Display )