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

feat(rviz_plugin): console meter is too large on the Rviz with FHD display, isn't it? #587

Merged
merged 3 commits into from
May 25, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
Prev Previous commit
scaling
Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
  • Loading branch information
TakaHoribe committed May 24, 2022
commit 6dc12a92b61fdcbe6ae881c752ff6e0977675460
10 changes: 6 additions & 4 deletions common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,12 @@ namespace rviz_plugins
MaxVelocityDisplay::MaxVelocityDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
const bool large_screen = screen_info->height > 2000;
const auto left = large_screen ? 595 : 297;
const auto top = large_screen ? 280 : 140;
const auto length = large_screen ? 96 : 48;

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",
Expand Down
9 changes: 5 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 @@ -26,10 +26,11 @@ ConsoleMeterDisplay::ConsoleMeterDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

const bool large_screen = screen_info->height > 2000;
const auto left = large_screen ? 512 : 256;
const auto top = large_screen ? 128 : 64;
const auto length = large_screen ? 256 : 128;
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);
Expand Down
10 changes: 6 additions & 4 deletions common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,12 @@ SteeringAngleDisplay::SteeringAngleDisplay()
.c_str())
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));
const bool large_screen = screen_info->height > 2000;
const auto left = large_screen ? 128 : 64;
const auto top = large_screen ? 128 : 64;
const auto length = large_screen ? 256 : 128;

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);
Expand Down
11 changes: 6 additions & 5 deletions common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,12 @@ TurnSignalDisplay::TurnSignalDisplay()
{
const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL));

const bool large_screen = screen_info->height > 2000;
const auto left = large_screen ? 196 : 98;
const auto top = large_screen ? 350 : 175;
const auto width = large_screen ? 512 : 256;
const auto height = large_screen ? 256 : 128;
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", left, "Left of the plotter window", this, SLOT(updateVisualization()), this);
Expand Down