src
rviz
default_plugin
point_cloud_display.cpp
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, Willow Garage, Inc.
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
30
#include <OgreSceneNode.h>
31
#include <OgreSceneManager.h>
32
33
#include <
ros/time.h
>
34
35
#include "
rviz/default_plugin/point_cloud_common.h
"
36
#include "
rviz/display_context.h
"
37
#include "
rviz/frame_manager.h
"
38
#include "
rviz/ogre_helpers/point_cloud.h
"
39
#include "
rviz/properties/int_property.h
"
40
41
#include "
point_cloud_display.h
"
42
43
namespace
rviz
44
{
45
PointCloudDisplay::PointCloudDisplay
() : point_cloud_common_(new
PointCloudCommon
(this))
46
{
47
queue_size_property_
=
new
IntProperty
(
48
"Queue Size"
, 10,
49
"Advanced: set the size of the incoming PointCloud message queue. "
50
" Increasing this is useful if your incoming TF data is delayed significantly "
51
"from your PointCloud data, but it can greatly increase memory usage if the messages are big."
,
52
this
, SLOT(
updateQueueSize
()));
53
}
54
55
PointCloudDisplay::~PointCloudDisplay
()
56
{
57
PointCloudDisplay::unsubscribe
();
58
delete
point_cloud_common_
;
59
}
60
61
void
PointCloudDisplay::onInitialize
()
62
{
63
// Use the threaded queue for processing of incoming messages
64
update_nh_
.
setCallbackQueue
(
context_
->
getThreadedQueue
());
65
66
MFDClass::onInitialize
();
67
point_cloud_common_
->
initialize
(
context_
,
scene_node_
);
68
}
69
70
void
PointCloudDisplay::updateQueueSize
()
71
{
72
tf_filter_
->
setQueueSize
((uint32_t)
queue_size_property_
->
getInt
());
73
}
74
75
void
PointCloudDisplay::processMessage
(
const
sensor_msgs::PointCloudConstPtr& cloud)
76
{
77
point_cloud_common_
->
addMessage
(cloud);
78
}
79
80
void
PointCloudDisplay::update
(
float
wall_dt,
float
ros_dt)
81
{
82
point_cloud_common_
->
update
(wall_dt, ros_dt);
83
}
84
85
void
PointCloudDisplay::reset
()
86
{
87
MFDClass::reset
();
88
point_cloud_common_
->
reset
();
89
}
90
91
}
// namespace rviz
92
93
#include <
pluginlib/class_list_macros.hpp
>
94
PLUGINLIB_EXPORT_CLASS
(
rviz::PointCloudDisplay
,
rviz::Display
)
rviz::MessageFilterDisplay< sensor_msgs::PointCloud >::tf_filter_
tf2_ros::MessageFilter< sensor_msgs::PointCloud > * tf_filter_
Definition:
message_filter_display.h:200
rviz::MessageFilterDisplay< sensor_msgs::PointCloud >::reset
void reset() override
Definition:
message_filter_display.h:108
rviz::PointCloudDisplay::~PointCloudDisplay
~PointCloudDisplay() override
Definition:
point_cloud_display.cpp:55
point_cloud_display.h
time.h
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition:
display.h:287
rviz::PointCloudDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition:
point_cloud_display.cpp:85
rviz::Display::update_nh_
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition:
display.h:300
rviz::PointCloudDisplay::processMessage
void processMessage(const sensor_msgs::PointCloudConstPtr &cloud) override
Process a single message. Overridden from MessageFilterDisplay.
Definition:
point_cloud_display.cpp:75
int_property.h
rviz::PointCloudCommon::initialize
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Definition:
point_cloud_common.cpp:366
rviz::MessageFilterDisplay< sensor_msgs::PointCloud >::unsubscribe
virtual void unsubscribe()
Definition:
message_filter_display.h:156
rviz::IntProperty
Property specialized to provide max/min enforcement for integers.
Definition:
int_property.h:37
rviz
Definition:
add_display_dialog.cpp:54
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition:
display.h:295
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition:
point_cloud_common.h:84
display_context.h
rviz::Display
Definition:
display.h:63
class_list_macros.hpp
rviz::PointCloudDisplay::PointCloudDisplay
PointCloudDisplay()
Definition:
point_cloud_display.cpp:45
rviz::PointCloudCommon::addMessage
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Definition:
point_cloud_common.cpp:938
point_cloud_common.h
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
tf2_ros::MessageFilter::setQueueSize
virtual void setQueueSize(uint32_t new_queue_size)
point_cloud.h
rviz::PointCloudDisplay::updateQueueSize
void updateQueueSize()
Definition:
point_cloud_display.cpp:70
rviz::IntProperty::getInt
virtual int getInt() const
Return the internal property value as an integer.
Definition:
int_property.h:74
rviz::PointCloudDisplay::onInitialize
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Definition:
point_cloud_display.cpp:61
rviz::PointCloudCommon::reset
void reset()
Definition:
point_cloud_common.cpp:507
rviz::PointCloudDisplay
Displays a point cloud of type sensor_msgs::PointCloud.
Definition:
point_cloud_display.h:56
rviz::MessageFilterDisplay< sensor_msgs::PointCloud >::onInitialize
void onInitialize() override
Definition:
message_filter_display.h:90
frame_manager.h
rviz::PointCloudDisplay::queue_size_property_
IntProperty * queue_size_property_
Definition:
point_cloud_display.h:77
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::PointCloudDisplay::point_cloud_common_
PointCloudCommon * point_cloud_common_
Definition:
point_cloud_display.h:79
rviz::DisplayContext::getThreadedQueue
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
rviz::PointCloudCommon::update
void update(float wall_dt, float ros_dt)
Definition:
point_cloud_common.cpp:519
rviz::PointCloudDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition:
point_cloud_display.cpp:80
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25