Skip to content

Commit

Permalink
Increase visual testing stability (#344)
Browse files Browse the repository at this point in the history
* Fix GridCells display updating of colour to all grid cells

* Fix image_display visual test

* Fix GridCellsDisplay

- setPickColor only sets pick color for selection handlers
- introduce setColor to actually set the points' colour

* Fix uncrustify in PointCloud

* Use different sleeping mechanism in publisher to prevent blocking

Use std::this_thread::sleep_for() instead of rclcpp::WallRate::sleep_for()
  • Loading branch information
greimela-si authored and wjwwood committed Aug 9, 2018
1 parent 3931ade commit 00f7efb
Show file tree
Hide file tree
Showing 7 changed files with 22 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC GridCellsDisplay : public

private Q_SLOTS:
void updateAlpha();
void updateColor();

private:
bool messageIsValid(nav_msgs::msg::GridCells::ConstSharedPtr msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ GridCellsDisplay::GridCellsDisplay()
: last_frame_count_(uint64_t(-1))
{
color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(25, 255, 0),
"Color of the grid cells.", this);
"Color of the grid cells.", this, SLOT(updateColor()));

alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 1.0f,
"Amount of transparency to apply to the cells.",
Expand Down Expand Up @@ -101,6 +101,12 @@ void GridCellsDisplay::updateAlpha()
context_->queueRender();
}

void GridCellsDisplay::updateColor()
{
cloud_->setColor(rviz_common::properties::qtToOgre(color_property_->getColor()));
context_->queueRender();
}

void GridCellsDisplay::processMessage(nav_msgs::msg::GridCells::ConstSharedPtr msg)
{
if (context_->getFrameCount() == last_frame_count_) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,6 @@ ImageDisplay::ImageDisplay(std::unique_ptr<ROSImageTextureIface> texture)
void ImageDisplay::onInitialize()
{
RTDClass::onInitialize();
topic_property_->setValue("image");

updateNormalizeOptions();
setupScreenRectangle();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ TEST_F(VisualTestFixture, test_image_display_with_published_image) {
setCamLookAt(Ogre::Vector3(0, 0, 0));

auto image_display = addDisplay<ImageDisplayPageObject>();
image_display->setTopic("/image");

captureRenderWindow(image_display);

Expand Down
3 changes: 3 additions & 0 deletions rviz_rendering/include/rviz_rendering/objects/point_cloud.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,9 @@ class PointCloud : public Ogre::MovableObject
RVIZ_RENDERING_PUBLIC
void setAlpha(float alpha, bool per_point_alpha = false);

RVIZ_RENDERING_PUBLIC
void setColor(const Ogre::ColourValue & color);

RVIZ_RENDERING_PUBLIC
void setPickColor(const Ogre::ColourValue & color);

Expand Down
8 changes: 8 additions & 0 deletions rviz_rendering/src/rviz_rendering/objects/point_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -455,6 +455,14 @@ void PointCloud::setAlpha(float alpha, bool per_point_alpha)
}
}

void PointCloud::setColor(const Ogre::ColourValue & color)
{
for (auto & point : points_) {
point.setColor(color.r, color.g, color.b, color.a);
}
regenerateAll();
}

void PointCloud::addPoints(
std::vector<Point>::iterator start_iterator,
std::vector<Point>::iterator stop_iterator)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#ifndef RVIZ_VISUAL_TESTING_FRAMEWORK__VISUAL_TEST_PUBLISHER_HPP_
#define RVIZ_VISUAL_TESTING_FRAMEWORK__VISUAL_TEST_PUBLISHER_HPP_

#include <chrono>
#include <memory>
#include <string>
#include <thread>
Expand Down Expand Up @@ -86,7 +87,6 @@ class VisualTestPublisher
auto transformer_publisher_node = std::make_shared<rclcpp::Node>("static_transform_publisher");
tf2_ros::StaticTransformBroadcaster broadcaster(transformer_publisher_node);

rclcpp::WallRate loop_rate(0.2);
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(transformer_publisher_node);

Expand All @@ -101,7 +101,7 @@ class VisualTestPublisher
broadcaster.sendTransform(msg);
}
executor.spin_some();
loop_rate.sleep();
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}
}

Expand Down

0 comments on commit 00f7efb

Please sign in to comment.