Skip to content

Commit

Permalink
Merge pull request #1471 from tier4/fix/sonor-cloud-issue-8-2
Browse files Browse the repository at this point in the history
Fix/sonor cloud issue 8-2
  • Loading branch information
hakuturu583 authored Dec 5, 2024
2 parents 06d9815 + ec9cc16 commit fd9d083
Showing 1 changed file with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
* but the initial value of 35.0 is set to ensure a default size that is likely suitable for most screens.
* The scaling factor adjusts this size to ensure readability across various resolutions.
*/
const float text_size = scale * 35.0;
const float text_size = scale * 35.0f;

/// @note Define initial value of left edge position of condition results panel
const int left = 0;
Expand All @@ -60,21 +60,21 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
* The purpose of this calculation is to position the top edge of the panel at an appropriate place on the screen,
* again scaling according to screen resolution to maintain a consistent look across different devices.
*/
const int top = static_cast<int>(std::round(450 * scale));
const auto top = static_cast<int>(std::round(450 * scale));

/**
* @note Define initial value of horizontal length of condition results panel.
* The reason 2000 is hard-coded here is because that number displayed most beautifully when we tested the operation on a 4K/non 4K display.
* Also, this number can be set via the rviz GUI.
*/
const int length = static_cast<int>(std::round(2000 * scale));
const auto length = static_cast<int>(std::round(2000 * scale));

/**
* @note Define initial value of width of condition results panel.
* The reason 2000 is hard-coded here is because that number displayed most beautifully when we tested the operation on a 4K/non 4K display.
* Also, this number can be set via the rviz GUI.
*/
const int width = static_cast<int>(std::round(2000 * scale));
const auto width = static_cast<int>(std::round(2000 * scale));

property_topic_name_ = std::make_unique<rviz_common::properties::StringProperty>(
"Topic", "/simulation/context", "The topic on which to publish simulation context.", this,
Expand All @@ -99,7 +99,7 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
"This property controls the scaling factor for the text size on the panel. Setting a higher "
"value results in larger text, making the displayed information easier to read.",
this, SLOT(updateVisualization()), this);
property_value_scale_->setMin(0.01);
property_value_scale_->setMin(0.01f);
}

VisualizationConditionGroupsDisplay::~VisualizationConditionGroupsDisplay()
Expand Down Expand Up @@ -174,7 +174,7 @@ void VisualizationConditionGroupsDisplay::processMessage(const Context::ConstSha
// QColor text_color = property_text_color_->getColor();
QColor text_color(property_text_color_->getColor());
text_color.setAlpha(255);
painter.setPen(QPen(text_color, static_cast<int>(2), Qt::SolidLine));
painter.setPen(QPen(text_color, 2, Qt::SolidLine));
QFont font = painter.font();
font.setPixelSize(std::max(static_cast<int>(property_value_scale_->getFloat()), 1));
font.setBold(true);
Expand Down Expand Up @@ -262,7 +262,7 @@ void VisualizationConditionGroupsDisplay::processEvent(const YAML::Node & event_
std::string event_name;
try {
event_name = event_node["name"].as<std::string>();
} catch (const YAML::BadConversion & e) {
} catch (const YAML::BadConversion &) {
event_name = "";
}
if (event_name.empty()) {
Expand Down

0 comments on commit fd9d083

Please sign in to comment.