Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Dec 19, 2024
1 parent be10038 commit f263213
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 18 deletions.
12 changes: 7 additions & 5 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,15 @@
from launch_ros.substitutions import FindPackageShare
import yaml


def get_control_cmd_topic(context):
is_redundant = LaunchConfiguration('launch_redundancy_system_components').perform(context)
system_run_mode = LaunchConfiguration('system_run_mode').perform(context)
is_redundant = LaunchConfiguration("launch_redundancy_system_components").perform(context)
system_run_mode = LaunchConfiguration("system_run_mode").perform(context)

if is_redundant.lower() == "true" and system_run_mode.lower() == "planning_simulation":
return "/main/control/command/control_cmd"
return "/control/command/control_cmd"

if is_redundant.lower() == 'true' and system_run_mode.lower() == 'planning_simulation':
return '/main/control/command/control_cmd'
return '/control/command/control_cmd'

def launch_setup(context, *args, **kwargs):
with open(LaunchConfiguration("vehicle_param_file").perform(context), "r") as f:
Expand Down
28 changes: 15 additions & 13 deletions system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,9 +141,8 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options)

void DummyDiagPublisher::handleParameterSetting()
{

param_callback_handle_ = this->add_on_set_parameters_callback(
[this](const std::vector<rclcpp::Parameter> & parameters) {
param_callback_handle_ =
this->add_on_set_parameters_callback([this](const std::vector<rclcpp::Parameter> & parameters) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;

Expand All @@ -157,33 +156,36 @@ void DummyDiagPublisher::handleParameterSetting()
auto new_status = convertStrToStatus(parameter.as_string());
if (new_status) {
diag.status = *new_status;
RCLCPP_INFO(this->get_logger(), "Updated %s status to: %s",
diag.name.c_str(), parameter.as_string().c_str());
RCLCPP_INFO(
this->get_logger(), "Updated %s status to: %s", diag.name.c_str(),
parameter.as_string().c_str());
} else {
result.successful = false;
result.reason = "Invalid status value for: " + param_name;
RCLCPP_WARN(this->get_logger(), "Invalid status value for %s: %s",
diag.name.c_str(), parameter.as_string().c_str());
RCLCPP_WARN(
this->get_logger(), "Invalid status value for %s: %s", diag.name.c_str(),
parameter.as_string().c_str());
}
} else if (param_name == diag.name + ".is_active") {
param_found = true;
diag.is_active = parameter.as_bool();
RCLCPP_INFO(this->get_logger(), "Updated %s is_active to: %s",
diag.name.c_str(), diag.is_active ? "true" : "false");
RCLCPP_INFO(
this->get_logger(), "Updated %s is_active to: %s", diag.name.c_str(),
diag.is_active ? "true" : "false");
}
}

if (!param_found) {
result.successful = false;
result.reason = "Parameter not registered: " + parameter.get_name();
RCLCPP_WARN(this->get_logger(), "Attempted to set unregistered parameter: %s",
parameter.get_name().c_str());
RCLCPP_WARN(
this->get_logger(), "Attempted to set unregistered parameter: %s",
parameter.get_name().c_str());
}
}

return result;
}
);
});
}

DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options)
Expand Down

0 comments on commit f263213

Please sign in to comment.