Skip to content

Commit f8ff1f2

Browse files
TakaHoribeboyali
authored andcommitted
feat(rviz_plugin): console meter is too large on the Rviz with FHD display, isn't it? (tier4#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>
1 parent 066fe8d commit f8ff1f2

File tree

4 files changed

+53
-14
lines changed

4 files changed

+53
-14
lines changed

common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp

+12-3
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <rviz_common/uniform_string_stream.hpp>
2020

2121
#include <OgreHardwarePixelBuffer.h>
22+
#include <X11/Xlib.h>
2223

2324
#include <algorithm>
2425
#include <iomanip>
@@ -28,20 +29,28 @@ namespace rviz_plugins
2829
{
2930
MaxVelocityDisplay::MaxVelocityDisplay()
3031
{
32+
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
33+
34+
constexpr float hight_4k = 2160.0;
35+
const float scale = static_cast<float>(screen_info->height) / hight_4k;
36+
const int left = static_cast<int>(std::round(595 * scale));
37+
const int top = static_cast<int>(std::round(280 * scale));
38+
const int length = static_cast<int>(std::round(96 * scale));
39+
3140
property_topic_name_ = new rviz_common::properties::StringProperty(
3241
"Topic", "/planning/scenario_planning/current_max_velocity",
3342
"The topic on which to publish max velocity.", this, SLOT(updateTopic()), this);
3443
property_text_color_ = new rviz_common::properties::ColorProperty(
3544
"Text Color", QColor(255, 255, 255), "text color", this, SLOT(updateVisualization()), this);
3645
property_left_ = new rviz_common::properties::IntProperty(
37-
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
46+
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
3847
property_left_->setMin(0);
3948
property_top_ = new rviz_common::properties::IntProperty(
40-
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
49+
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
4150
property_top_->setMin(0);
4251

4352
property_length_ = new rviz_common::properties::IntProperty(
44-
"Length", 96, "Length of the plotter window", this, SLOT(updateVisualization()), this);
53+
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
4554
property_length_->setMin(10);
4655
property_value_scale_ = new rviz_common::properties::FloatProperty(
4756
"Value Scale", 1.0 / 4.0, "Value scale", this, SLOT(updateVisualization()), this);

common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp

+13-4
Original file line numberDiff line numberDiff line change
@@ -17,23 +17,32 @@
1717
#include <QPainter>
1818
#include <rviz_common/uniform_string_stream.hpp>
1919

20-
#include <algorithm>
20+
#include <X11/Xlib.h>
2121

22+
#include <algorithm>
2223
namespace rviz_plugins
2324
{
2425
ConsoleMeterDisplay::ConsoleMeterDisplay()
2526
{
27+
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
28+
29+
constexpr float hight_4k = 2160.0;
30+
const float scale = static_cast<float>(screen_info->height) / hight_4k;
31+
const auto left = static_cast<int>(std::round(512 * scale));
32+
const auto top = static_cast<int>(std::round(128 * scale));
33+
const auto length = static_cast<int>(std::round(256 * scale));
34+
2635
property_text_color_ = new rviz_common::properties::ColorProperty(
2736
"Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this);
2837
property_left_ = new rviz_common::properties::IntProperty(
29-
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
38+
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
3039
property_left_->setMin(0);
3140
property_top_ = new rviz_common::properties::IntProperty(
32-
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
41+
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
3342
property_top_->setMin(0);
3443

3544
property_length_ = new rviz_common::properties::IntProperty(
36-
"Length", 256, "Length of the plotter window", this, SLOT(updateVisualization()), this);
45+
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
3746
property_length_->setMin(10);
3847
property_value_height_offset_ = new rviz_common::properties::IntProperty(
3948
"Value height offset", 0, "Height offset of the plotter window", this,

common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp

+13-3
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818
#include <ament_index_cpp/get_package_share_directory.hpp>
1919
#include <rviz_common/uniform_string_stream.hpp>
2020

21+
#include <X11/Xlib.h>
22+
2123
#include <algorithm>
2224
#include <iomanip>
2325
#include <memory>
@@ -31,17 +33,25 @@ SteeringAngleDisplay::SteeringAngleDisplay()
3133
"/images/handle.png")
3234
.c_str())
3335
{
36+
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
37+
38+
constexpr float hight_4k = 2160.0;
39+
const float scale = static_cast<float>(screen_info->height) / hight_4k;
40+
const auto left = static_cast<int>(std::round(128 * scale));
41+
const auto top = static_cast<int>(std::round(128 * scale));
42+
const auto length = static_cast<int>(std::round(256 * scale));
43+
3444
property_text_color_ = new rviz_common::properties::ColorProperty(
3545
"Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this);
3646
property_left_ = new rviz_common::properties::IntProperty(
37-
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
47+
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
3848
property_left_->setMin(0);
3949
property_top_ = new rviz_common::properties::IntProperty(
40-
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
50+
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
4151
property_top_->setMin(0);
4252

4353
property_length_ = new rviz_common::properties::IntProperty(
44-
"Length", 256, "Length of the plotter window", this, SLOT(updateVisualization()), this);
54+
"Length", length, "Length of the plotter window", this, SLOT(updateVisualization()), this);
4555
property_length_->setMin(10);
4656
property_value_height_offset_ = new rviz_common::properties::IntProperty(
4757
"Value height offset", 0, "Height offset of the plotter window", this,

common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp

+15-4
Original file line numberDiff line numberDiff line change
@@ -18,22 +18,33 @@
1818
#include <ament_index_cpp/get_package_share_directory.hpp>
1919
#include <rviz_common/uniform_string_stream.hpp>
2020

21+
#include <X11/Xlib.h>
22+
2123
namespace rviz_plugins
2224
{
2325
TurnSignalDisplay::TurnSignalDisplay()
2426
{
27+
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
28+
29+
constexpr float hight_4k = 2160.0;
30+
const float scale = static_cast<float>(screen_info->height) / hight_4k;
31+
const auto left = static_cast<int>(std::round(196 * scale));
32+
const auto top = static_cast<int>(std::round(350 * scale));
33+
const auto width = static_cast<int>(std::round(512 * scale));
34+
const auto height = static_cast<int>(std::round(256 * scale));
35+
2536
property_left_ = new rviz_common::properties::IntProperty(
26-
"Left", 128, "Left of the plotter window", this, SLOT(updateVisualization()), this);
37+
"Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
2738
property_left_->setMin(0);
2839
property_top_ = new rviz_common::properties::IntProperty(
29-
"Top", 128, "Top of the plotter window", this, SLOT(updateVisualization()));
40+
"Top", top, "Top of the plotter window", this, SLOT(updateVisualization()));
3041
property_top_->setMin(0);
3142

3243
property_width_ = new rviz_common::properties::IntProperty(
33-
"Width", 256, "Width of the plotter window", this, SLOT(updateVisualization()), this);
44+
"Width", width, "Width of the plotter window", this, SLOT(updateVisualization()), this);
3445
property_width_->setMin(10);
3546
property_height_ = new rviz_common::properties::IntProperty(
36-
"Height", 256, "Height of the plotter window", this, SLOT(updateVisualization()), this);
47+
"Height", height, "Height of the plotter window", this, SLOT(updateVisualization()), this);
3748
property_height_->setMin(10);
3849
}
3950

0 commit comments

Comments
 (0)