Skip to content

Commit

Permalink
feat(rviz_plugin): console meter is too large on the Rviz with FHD di…
Browse files Browse the repository at this point in the history
…splay, isn't it? (autowarefoundation#587)

* feat(tier4_planning/vehicle_plugin): make plugins size scalable

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* remove space

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* scaling

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
  • Loading branch information
TakaHoribe authored and ktro2828 committed Jun 7, 2022
1 parent e607d96 commit 7a7688f
Show file tree
Hide file tree
Showing 4 changed files with 53 additions and 14 deletions.
15 changes: 12 additions & 3 deletions common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <rviz_common/uniform_string_stream.hpp>

#include <OgreHardwarePixelBuffer.h>
#include <X11/Xlib.h>

#include <algorithm>
#include <iomanip>
Expand All @@ -28,20 +29,28 @@ namespace rviz_plugins
{
MaxVelocityDisplay::MaxVelocityDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

constexpr float hight_4k = 2160.0;
const float scale = static_cast<float>(screen_info->height) / hight_4k;
const int left = static_cast<int>(std::round(595 * scale));
const int top = static_cast<int>(std::round(280 * scale));
const int length = static_cast<int>(std::round(96 * scale));

property_topic_name_ = new rviz_common::properties::StringProperty(
"Topic", "/planning/scenario_planning/current_max_velocity",
"The topic on which to publish max velocity.", this, SLOT(updateTopic()), this);
property_text_color_ = new rviz_common::properties::ColorProperty(
"Text Color", QColor(255, 255, 255), "text color", this, SLOT(updateVisualization()), this);
property_left_ = new rviz_common::properties::IntProperty(
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
property_left_->setMin(0);
property_top_ = new rviz_common::properties::IntProperty(
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
property_top_->setMin(0);

property_length_ = new rviz_common::properties::IntProperty(
"Length", 96, "Length of the plotter window", this, SLOT(updateVisualization()), this);
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
property_length_->setMin(10);
property_value_scale_ = new rviz_common::properties::FloatProperty(
"Value Scale", 1.0 / 4.0, "Value scale", this, SLOT(updateVisualization()), this);
Expand Down
17 changes: 13 additions & 4 deletions common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,23 +17,32 @@
#include <QPainter>
#include <rviz_common/uniform_string_stream.hpp>

#include <algorithm>
#include <X11/Xlib.h>

#include <algorithm>
namespace rviz_plugins
{
ConsoleMeterDisplay::ConsoleMeterDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

constexpr float hight_4k = 2160.0;
const float scale = static_cast<float>(screen_info->height) / hight_4k;
const auto left = static_cast<int>(std::round(512 * scale));
const auto top = static_cast<int>(std::round(128 * scale));
const auto length = static_cast<int>(std::round(256 * scale));

property_text_color_ = new rviz_common::properties::ColorProperty(
"Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this);
property_left_ = new rviz_common::properties::IntProperty(
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
property_left_->setMin(0);
property_top_ = new rviz_common::properties::IntProperty(
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
property_top_->setMin(0);

property_length_ = new rviz_common::properties::IntProperty(
"Length", 256, "Length of the plotter window", this, SLOT(updateVisualization()), this);
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
property_length_->setMin(10);
property_value_height_offset_ = new rviz_common::properties::IntProperty(
"Value height offset", 0, "Height offset of the plotter window", this,
Expand Down
16 changes: 13 additions & 3 deletions common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rviz_common/uniform_string_stream.hpp>

#include <X11/Xlib.h>

#include <algorithm>
#include <iomanip>
#include <memory>
Expand All @@ -31,17 +33,25 @@ SteeringAngleDisplay::SteeringAngleDisplay()
"/images/handle.png")
.c_str())
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

constexpr float hight_4k = 2160.0;
const float scale = static_cast<float>(screen_info->height) / hight_4k;
const auto left = static_cast<int>(std::round(128 * scale));
const auto top = static_cast<int>(std::round(128 * scale));
const auto length = static_cast<int>(std::round(256 * scale));

property_text_color_ = new rviz_common::properties::ColorProperty(
"Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this);
property_left_ = new rviz_common::properties::IntProperty(
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
property_left_->setMin(0);
property_top_ = new rviz_common::properties::IntProperty(
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
property_top_->setMin(0);

property_length_ = new rviz_common::properties::IntProperty(
"Length", 256, "Length of the plotter window", this, SLOT(updateVisualization()), this);
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
property_length_->setMin(10);
property_value_height_offset_ = new rviz_common::properties::IntProperty(
"Value height offset", 0, "Height offset of the plotter window", this,
Expand Down
19 changes: 15 additions & 4 deletions common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,22 +18,33 @@
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rviz_common/uniform_string_stream.hpp>

#include <X11/Xlib.h>

namespace rviz_plugins
{
TurnSignalDisplay::TurnSignalDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

constexpr float hight_4k = 2160.0;
const float scale = static_cast<float>(screen_info->height) / hight_4k;
const auto left = static_cast<int>(std::round(196 * scale));
const auto top = static_cast<int>(std::round(350 * scale));
const auto width = static_cast<int>(std::round(512 * scale));
const auto height = static_cast<int>(std::round(256 * scale));

property_left_ = new rviz_common::properties::IntProperty(
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
property_left_->setMin(0);
property_top_ = new rviz_common::properties::IntProperty(
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
property_top_->setMin(0);

property_width_ = new rviz_common::properties::IntProperty(
"Width", 256, "Width of the plotter window", this, SLOT(updateVisualization()), this);
"Width", width, "Width of the plotter window", this, SLOT(updateVisualization()), this);
property_width_->setMin(10);
property_height_ = new rviz_common::properties::IntProperty(
"Height", 256, "Height of the plotter window", this, SLOT(updateVisualization()), this);
"Height", height, "Height of the plotter window", this, SLOT(updateVisualization()), this);
property_height_->setMin(10);
}

Expand Down

0 comments on commit 7a7688f

Please sign in to comment.