Skip to content

Commit

Permalink
feat(parameters_visualization): code refactoring for styling
Browse files Browse the repository at this point in the history
  • Loading branch information
Ahmed Ebrahim committed Sep 27, 2024
1 parent 536373f commit 6627841
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <scenario_simulator_exception/exception.hpp>
#include <simple_junit/junit5.hpp>
#include <utility>
#include <std_msgs/msg/string.hpp>
#include <utility>

#define INTERPRETER_INFO_STREAM(...) \
RCLCPP_INFO_STREAM(get_logger(), "\x1b[32m" << __VA_ARGS__ << "\x1b[0m")
Expand All @@ -51,7 +51,6 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode,
{
using Context = openscenario_interpreter_msgs::msg::Context;
const rclcpp_lifecycle::LifecyclePublisher<Context>::SharedPtr publisher_of_context;
const rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>::SharedPtr publisher_of_params;
Expand Down Expand Up @@ -82,7 +81,7 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode,
using Result = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
bool waiting_for_engagement_to_be_completed = false; // NOTE: DIRTY HACK!!!
std_msgs::msg::String test_iteration_params_str = std_msgs::msg::String();
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ namespace openscenario_interpreter
Interpreter::Interpreter(const rclcpp::NodeOptions & options)
: rclcpp_lifecycle::LifecycleNode("openscenario_interpreter", options),
publisher_of_context(create_publisher<Context>("context", rclcpp::QoS(1).transient_local())),
publisher_of_params(create_publisher<std_msgs::msg::String>("test_iteration_parameters", rclcpp::QoS(1).transient_local())),
publisher_of_params(create_publisher<std_msgs::msg::String>(
"test_iteration_parameters", rclcpp::QoS(1).transient_local())),
local_frame_rate(30),
local_real_time_factor(1.0),
osc_path(""),
Expand Down Expand Up @@ -184,7 +185,6 @@ auto Interpreter::engaged() const -> bool

auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result
{

auto evaluate_storyboard = [this]() {
withExceptionHandler(
[this](auto &&...) {
Expand Down Expand Up @@ -250,7 +250,6 @@ auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result

publisher_of_context->on_activate();
publisher_of_params->on_activate();


assert(publisher_of_context->is_activated());
assert(publisher_of_params->is_activated());
Expand Down Expand Up @@ -323,11 +322,10 @@ auto Interpreter::reset() -> void
publisher_of_context->on_deactivate();
}

if (publisher_of_params->is_activated()) {
if (publisher_of_params->is_activated()) {
publisher_of_params->on_deactivate();
}


if (not has_parameter("initialize_duration")) {
declare_parameter<int>("initialize_duration", 30);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,12 @@ VisualizationParametersDisplay::VisualizationParametersDisplay()
const float scale = static_cast<float>(screen_info->height) / hight_4k;

/**
* @note The multiplication of 35.0 is used to determine the initial text size in the panel.
* @note The multiplication of 35.0 is used to determine the initial text size in the panel.
* This value is a base size that is then scaled according to the screen resolution.
* The 'Value Scale' property allows users to adjust the scaling factor of this text size later on,
* 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.
* The 'Value Scale' property allows users to adjust the scaling factor of this text size later
* on, 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;

Expand All @@ -53,30 +54,32 @@ VisualizationParametersDisplay::VisualizationParametersDisplay()

/**
* @note Define initial value of top edge position of condition results panel
* The multiplication of 450 sets the initial top edge position of the condition results panel.
* Like the width and length, this is a predefined base value, not necessarily linked to any value set from the Top property.
* 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.
* The multiplication of 450 sets the initial top edge position of the condition results panel.
* Like the width and length, this is a predefined base value, not necessarily linked to any value
* set from the Top property. 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));

/**
* @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.
* 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));

/**
* @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.
* 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));

property_topic_name_ = new rviz_common::properties::StringProperty(
"Topic", "/simulation/test_iteration_parameters", "The topic on which to test iteration parameters are published.", this,
SLOT(updateTopic()), this);
"Topic", "/simulation/test_iteration_parameters",
"The topic on which to test iteration parameters are published.", 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(
Expand Down Expand Up @@ -156,7 +159,8 @@ void VisualizationParametersDisplay::subscribe()

void VisualizationParametersDisplay::unsubscribe() { test_iteration_params_sub_.reset(); }

void VisualizationParametersDisplay::processMessage(const std_msgs::msg::String::ConstSharedPtr msg_ptr)
void VisualizationParametersDisplay::processMessage(
const std_msgs::msg::String::ConstSharedPtr msg_ptr)
{
if (!overlay_->isVisible()) return;

Expand Down

0 comments on commit 6627841

Please sign in to comment.