Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

MessageFilterDisplay: add queue-size property #1428

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 11 additions & 5 deletions src/rviz/default_plugin/effort_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -536,23 +536,23 @@ class MessageFilterJointStateDisplay: public _RosTopicDisplay

virtual void onInitialize()
{
// TODO(wjwwood): remove this and use tf2 interface instead
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

auto tf_client = context_->getTFClient();
auto tf_client = context_->getTFClient();

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
tf_filter_ = new tf::MessageFilterJointState( *tf_client,
fixed_frame_.toStdString(), 10, update_nh_ );
fixed_frame_.toStdString(), queue_size_property_->getInt(), update_nh_ );

tf_filter_->connectInput( sub_ );
tf_filter_->registerCallback( boost::bind( &MessageFilterJointStateDisplay::incomingMessage, this, _1 ));
// TODO(wjwwood): remove this and use tf2 interface instead
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Expand Down Expand Up @@ -587,6 +587,12 @@ class MessageFilterJointStateDisplay: public _RosTopicDisplay
context_->queueRender();
}

virtual void updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
subscribe();
}

virtual void subscribe()
{
if( !isEnabled() )
Expand All @@ -596,7 +602,7 @@ class MessageFilterJointStateDisplay: public _RosTopicDisplay

try
{
sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 10 );
sub_.subscribe( update_nh_, topic_property_->getTopicStd(), queue_size_property_->getInt() );
setStatus( StatusProperty::Ok, "Topic", "OK" );
}
catch( ros::Exception& e )
Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/fluid_pressure_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ namespace rviz
FluidPressureDisplay::FluidPressureDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming FluidPressure message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your FluidPressure data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -76,11 +70,6 @@ void FluidPressureDisplay::onInitialize()
subProp("Max Intensity")->setValue(105000); // Typica 'high' atmosphereic pressure in Pascal
}

void FluidPressureDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void FluidPressureDisplay::processMessage( const sensor_msgs::FluidPressureConstPtr& msg )
{
// Filter any nan values out of the cloud. Any nan values that make it through to PointCloudBase
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/fluid_pressure_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::FluidPressureConstPtr& msg );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/illuminance_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ namespace rviz
IlluminanceDisplay::IlluminanceDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming Illuminance message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your Illuminance data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -76,11 +70,6 @@ void IlluminanceDisplay::onInitialize()
subProp("Max Intensity")->setValue(1000);
}

void IlluminanceDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void IlluminanceDisplay::processMessage( const sensor_msgs::IlluminanceConstPtr& msg )
{
// Filter any nan values out of the cloud. Any nan values that make it through to PointCloudBase
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/illuminance_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::IlluminanceConstPtr& msg );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/laser_scan_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,6 @@ LaserScanDisplay::LaserScanDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
, projector_( new laser_geometry::LaserProjection() )
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming LaserScan message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your LaserScan data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -73,11 +67,6 @@ void LaserScanDisplay::onInitialize()
point_cloud_common_->initialize( context_, scene_node_ );
}

void LaserScanDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void LaserScanDisplay::processMessage( const sensor_msgs::LaserScanConstPtr& scan )
{
sensor_msgs::PointCloudPtr cloud( new sensor_msgs::PointCloud );
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/laser_scan_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::LaserScanConstPtr& scan );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;

laser_geometry::LaserProjection* projector_;
Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/point_cloud2_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ namespace rviz
PointCloud2Display::PointCloud2Display()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming PointCloud2 message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your PointCloud2 data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -70,11 +64,6 @@ void PointCloud2Display::onInitialize()
point_cloud_common_->initialize( context_, scene_node_ );
}

void PointCloud2Display::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void PointCloud2Display::processMessage( const sensor_msgs::PointCloud2ConstPtr& cloud )
{
// Filter any nan values out of the cloud. Any nan values that make it through to PointCloudBase
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/point_cloud2_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,18 +59,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::PointCloud2ConstPtr& cloud );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/point_cloud_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,6 @@ namespace rviz
PointCloudDisplay::PointCloudDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming PointCloud message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your PointCloud data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -68,11 +62,6 @@ void PointCloudDisplay::onInitialize()
point_cloud_common_->initialize( context_, scene_node_ );
}

void PointCloudDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void PointCloudDisplay::processMessage( const sensor_msgs::PointCloudConstPtr& cloud )
{
point_cloud_common_->addMessage( cloud );
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/point_cloud_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,18 +63,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::PointCloudConstPtr& cloud );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
9 changes: 0 additions & 9 deletions src/rviz/default_plugin/range_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,6 @@ RangeDisplay::RangeDisplay()
"Number of prior measurements to display.",
this, SLOT( updateBufferLength() ));
buffer_length_property_->setMin( 1 );

queue_size_property_ = new IntProperty( "Queue Size", 100,
"Size of the tf message filter queue. It usually needs to be set at least as high as the number of sonar frames.",
this, SLOT( updateQueueSize() ));
}

void RangeDisplay::onInitialize()
Expand All @@ -84,11 +80,6 @@ void RangeDisplay::reset()
updateBufferLength();
}

void RangeDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void RangeDisplay::updateColorAndAlpha()
{
Ogre::ColourValue oc = color_property_->getOgreColor();
Expand Down
2 changes: 0 additions & 2 deletions src/rviz/default_plugin/range_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,15 +70,13 @@ Q_OBJECT
private Q_SLOTS:
void updateBufferLength();
void updateColorAndAlpha();
void updateQueueSize();

private:
std::vector<Shape* > cones_; ///< Handles actually drawing the cones

ColorProperty* color_property_;
FloatProperty* alpha_property_;
IntProperty* buffer_length_property_;
IntProperty* queue_size_property_;
};

} // namespace range_plugin
Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/relative_humidity_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ namespace rviz
RelativeHumidityDisplay::RelativeHumidityDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming RelativeHumidity message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your RelativeHumidity data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -76,11 +70,6 @@ void RelativeHumidityDisplay::onInitialize()
subProp("Max Intensity")->setValue(1.0); // 100% relative humidity
}

void RelativeHumidityDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void RelativeHumidityDisplay::processMessage( const sensor_msgs::RelativeHumidityConstPtr& msg )
{
sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/relative_humidity_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::RelativeHumidityConstPtr& msg );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
11 changes: 0 additions & 11 deletions src/rviz/default_plugin/temperature_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ namespace rviz
TemperatureDisplay::TemperatureDisplay()
: point_cloud_common_( new PointCloudCommon( this ))
{
queue_size_property_ = new IntProperty( "Queue Size", 10,
"Advanced: set the size of the incoming Temperature message queue. "
" Increasing this is useful if your incoming TF data is delayed significantly "
"from your Temperature data, but it can greatly increase memory usage if the messages are big.",
this, SLOT( updateQueueSize() ));

// PointCloudCommon sets up a callback queue with a thread for each
// instance. Use that for processing incoming messages.
update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
Expand All @@ -77,11 +71,6 @@ void TemperatureDisplay::onInitialize()
subProp("Max Intensity")->setValue(100); // Water Boiling
}

void TemperatureDisplay::updateQueueSize()
{
tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
}

void TemperatureDisplay::processMessage( const sensor_msgs::TemperatureConstPtr& msg )
{
sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
Expand Down
5 changes: 0 additions & 5 deletions src/rviz/default_plugin/temperature_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,13 @@ Q_OBJECT

virtual void update( float wall_dt, float ros_dt );

private Q_SLOTS:
void updateQueueSize();

protected:
/** @brief Do initialization. Overridden from MessageFilterDisplay. */
virtual void onInitialize();

/** @brief Process a single message. Overridden from MessageFilterDisplay. */
virtual void processMessage( const sensor_msgs::TemperatureConstPtr& msg );

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
};

Expand Down
Loading