Skip to content

Commit be943cd

Browse files
bhagyeshagresarmergify[bot]
authored andcommitted
Simplify on_set_chained_mode implementations avoiding cpplint warnings (#1564)
(cherry picked from commit d8dc4b1) # Conflicts: # diff_drive_controller/src/diff_drive_controller.cpp # pid_controller/src/pid_controller.cpp
1 parent 5090d28 commit be943cd

File tree

4 files changed

+54
-10
lines changed

4 files changed

+54
-10
lines changed

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -607,6 +607,31 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(
607607

608608
return controller_interface::CallbackReturn::SUCCESS;
609609
}
610+
<<<<<<< HEAD
611+
=======
612+
613+
bool DiffDriveController::on_set_chained_mode(bool /*chained_mode*/) { return true; }
614+
615+
std::vector<hardware_interface::CommandInterface>
616+
DiffDriveController::on_export_reference_interfaces()
617+
{
618+
std::vector<hardware_interface::CommandInterface> reference_interfaces;
619+
reference_interfaces.reserve(reference_interfaces_.size());
620+
621+
reference_interfaces.push_back(
622+
hardware_interface::CommandInterface(
623+
get_node()->get_name() + std::string("/linear"), hardware_interface::HW_IF_VELOCITY,
624+
&reference_interfaces_[0]));
625+
626+
reference_interfaces.push_back(
627+
hardware_interface::CommandInterface(
628+
get_node()->get_name() + std::string("/angular"), hardware_interface::HW_IF_VELOCITY,
629+
&reference_interfaces_[1]));
630+
631+
return reference_interfaces;
632+
}
633+
634+
>>>>>>> d8dc4b1 (Simplify `on_set_chained_mode` implementations avoiding cpplint warnings (#1564))
610635
} // namespace diff_drive_controller
611636

612637
#include "class_loader/register_macro.hpp"

mecanum_drive_controller/src/mecanum_drive_controller.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -321,11 +321,7 @@ MecanumDriveController::on_export_reference_interfaces()
321321
return reference_interfaces;
322322
}
323323

324-
bool MecanumDriveController::on_set_chained_mode(bool chained_mode)
325-
{
326-
// Always accept switch to/from chained mode
327-
return true || chained_mode;
328-
}
324+
bool MecanumDriveController::on_set_chained_mode(bool /*chained_mode*/) { return true; }
329325

330326
controller_interface::CallbackReturn MecanumDriveController::on_activate(
331327
const rclcpp_lifecycle::State & /*previous_state*/)

pid_controller/src/pid_controller.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -358,11 +358,38 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
358358
return reference_interfaces;
359359
}
360360

361+
<<<<<<< HEAD
361362
bool PidController::on_set_chained_mode(bool chained_mode)
362363
{
363364
// Always accept switch to/from chained mode
364365
return true || chained_mode;
365366
}
367+
=======
368+
std::vector<hardware_interface::StateInterface> PidController::on_export_state_interfaces()
369+
{
370+
std::vector<hardware_interface::StateInterface> state_interfaces;
371+
state_interfaces.reserve(state_interfaces_values_.size());
372+
373+
state_interfaces_values_.resize(
374+
reference_and_state_dof_names_.size() * params_.reference_and_state_interfaces.size(),
375+
std::numeric_limits<double>::quiet_NaN());
376+
size_t index = 0;
377+
for (const auto & interface : params_.reference_and_state_interfaces)
378+
{
379+
for (const auto & dof_name : reference_and_state_dof_names_)
380+
{
381+
state_interfaces.push_back(
382+
hardware_interface::StateInterface(
383+
std::string(get_node()->get_name()) + "/" + dof_name, interface,
384+
&state_interfaces_values_[index]));
385+
++index;
386+
}
387+
}
388+
return state_interfaces;
389+
}
390+
391+
bool PidController::on_set_chained_mode(bool /*chained_mode*/) { return true; }
392+
>>>>>>> d8dc4b1 (Simplify `on_set_chained_mode` implementations avoiding cpplint warnings (#1564))
366393

367394
controller_interface::CallbackReturn PidController::on_activate(
368395
const rclcpp_lifecycle::State & /*previous_state*/)

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -379,11 +379,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
379379
return reference_interfaces;
380380
}
381381

382-
bool SteeringControllersLibrary::on_set_chained_mode(bool chained_mode)
383-
{
384-
// Always accept switch to/from chained mode
385-
return true || chained_mode;
386-
}
382+
bool SteeringControllersLibrary::on_set_chained_mode(bool /*chained_mode*/) { return true; }
387383

388384
controller_interface::CallbackReturn SteeringControllersLibrary::on_activate(
389385
const rclcpp_lifecycle::State & /*previous_state*/)

0 commit comments

Comments
 (0)