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

Increase visual testing stability #344

Merged
merged 5 commits into from
Aug 9, 2018
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
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()));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since this change I'm getting a compile error. Is there another repo I need to pull?

/home/developer/workspaces/ros2-dev0/src/ros2/rviz/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp: In member function ‘void rviz_default_plugins::displays::GridCellsDisplay::updateColor()’:
/home/developer/workspaces/ros2-dev0/src/ros2/rviz/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp:106:11: error: ‘using element_type = class rviz_rendering::PointCloud {aka class rviz_rendering::PointCloud}’ has no member named ‘setColor’; did you mean ‘setPickColor’?
   cloud_->setColor(rviz_common::properties::qtToOgre(color_property_->getColor()));
           ^~~~~~~~
           setPickColor

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What do you mean? It's passing on CI AFAIK.

In general, I wouldn't expect anything to work without all the repositories in the ros2.repos file being up-to-date.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The function was introduced in rviz_rendering::PointCloud in rviz_rendering with this PR. So if you recompile this repository, it should be fine.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The issue persisted after deleting build/rviz* and install/rviz* and building with --packages-above rcl. However, it is gone after deleting the entire build and install folders and rebuilding everything.

I don't know what happened. It's almost like there is a missing build_depend, but I do see it in the package.xml

<depend>rviz_rendering</depend>

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
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