Skip to content

Commit

Permalink
Fix clang tidy errors
Browse files Browse the repository at this point in the history
  • Loading branch information
evan-palmer committed Sep 15, 2024
1 parent 56ddca9 commit bde0c33
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,11 @@ auto ThrusterAllocationMatrixController::on_configure(const rclcpp_lifecycle::St
command_interfaces_.reserve(num_thrusters_);

reference_sub_ = get_node()->create_subscription<geometry_msgs::msg::Wrench>(
"~/reference", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<geometry_msgs::msg::Wrench> msg) {
"~/reference",
rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<geometry_msgs::msg::Wrench> msg) { // NOLINT
reference_.writeFromNonRT(msg);
}); // NOLINT
});

controller_state_pub_ = get_node()->create_publisher<auv_control_msgs::msg::MultiActuatorStateStamped>(
"~/status", rclcpp::SystemDefaultsQoS());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,9 @@ auto PolynomialThrustCurveController::on_configure(const rclcpp_lifecycle::State
command_interfaces_.reserve(1);

reference_sub_ = get_node()->create_subscription<std_msgs::msg::Float64>(
"~/reference", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<std_msgs::msg::Float64> msg) {
"~/reference", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<std_msgs::msg::Float64> msg) { // NOLINT
reference_.writeFromNonRT(msg);
}); // NOLINT
});

controller_state_pub_ =
get_node()->create_publisher<control_msgs::msg::SingleDOFStateStamped>("~/status", rclcpp::SystemDefaultsQoS());
Expand Down
16 changes: 10 additions & 6 deletions velocity_controllers/src/integral_sliding_mode_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ auto IntegralSlidingModeController::command_interface_configuration() const
command_interface_configuration.type = controller_interface::interface_configuration_type::INDIVIDUAL;

for (const auto & dof : dof_names_) {
if (params_.reference_controller.length() <= 0) {
if (params_.reference_controller.empty()) {
command_interface_configuration.names.emplace_back(dof + "/" + hardware_interface::HW_IF_EFFORT);
} else {
command_interface_configuration.names.emplace_back(
Expand Down Expand Up @@ -188,16 +188,20 @@ auto IntegralSlidingModeController::on_configure(const rclcpp_lifecycle::State &
system_state_values_.resize(DOF, std::numeric_limits<double>::quiet_NaN());

reference_sub_ = get_node()->create_subscription<geometry_msgs::msg::Twist>(
"~/reference", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<geometry_msgs::msg::Twist> msg) {
"~/reference",
rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<geometry_msgs::msg::Twist> msg) { // NOLINT
reference_.writeFromNonRT(msg);
}); // NOLINT

// If we aren't reading from the state interfaces, subscribe to the system state topic
if (params_.use_external_measured_states) {
system_state_sub_ = get_node()->create_subscription<geometry_msgs::msg::Twist>(
"~/system_state", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<geometry_msgs::msg::Twist> msg) {
"~/system_state",
rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<geometry_msgs::msg::Twist> msg) { // NOLINT
system_state_.writeFromNonRT(msg);
}); // NOLINT
});
}

// Configure the TF buffer and listener
Expand Down Expand Up @@ -248,9 +252,9 @@ auto IntegralSlidingModeController::on_deactivate(const rclcpp_lifecycle::State

auto IntegralSlidingModeController::on_set_chained_mode(bool /*chained_mode*/) -> bool { return true; }

controller_interface::return_type IntegralSlidingModeController::update_reference_from_subscribers(
auto IntegralSlidingModeController::update_reference_from_subscribers(
const rclcpp::Time & /*time*/,
const rclcpp::Duration & /*period*/)
const rclcpp::Duration & /*period*/) -> controller_interface::return_type
{
auto * current_reference = reference_.readFromNonRT();

Expand Down

0 comments on commit bde0c33

Please sign in to comment.