Skip to content

Commit

Permalink
Do some more variable renaming to the new nomenclature.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Aug 25, 2022
1 parent 9cee15a commit 0970d01
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
6 changes: 3 additions & 3 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -837,7 +837,7 @@ controller_interface::return_type ControllerManager::switch_controller(
// outdated. Keeping it up to date is not easy because of stopping controllers from multiple
// threads maybe we should not at all cache this but always search for the related controllers
// to a hardware when error in hardware happens
if (in_start_list)
if (in_activate_list)
{
std::vector<std::string> interface_names = {};

Expand Down Expand Up @@ -1718,7 +1718,7 @@ void ControllerManager::read(const rclcpp::Time & time, const rclcpp::Duration &

std::vector<ControllerSpec> & rt_controller_list =
rt_controllers_wrapper_.update_and_get_used_by_rt_list();
stop_controllers(rt_controller_list, stop_request);
deactivate_controllers(rt_controller_list, stop_request);
// TODO(destogl): do auto-start of broadcasters
}
}
Expand Down Expand Up @@ -1788,7 +1788,7 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration

std::vector<ControllerSpec> & rt_controller_list =
rt_controllers_wrapper_.update_and_get_used_by_rt_list();
stop_controllers(rt_controller_list, stop_request);
deactivate_controllers(rt_controller_list, stop_request);
// TODO(destogl): do auto-start of broadcasters
}
}
Expand Down
4 changes: 2 additions & 2 deletions hardware_interface/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class TestActuator : public ActuatorInterface
if (velocity_command_ == 28282828.0)
{
// reset value to get out from error on the next call - simplifies CM tests
position_command_ = 0.0;
velocity_command_ = 0.0;
return return_type::ERROR;
}
// The next line is for the testing purposes. We need value to be changed to be sure that
Expand All @@ -98,7 +98,7 @@ class TestActuator : public ActuatorInterface
if (velocity_command_ == 23232323.0)
{
// reset value to get out from error on the next call - simplifies CM tests
position_command_ = 0.0;
velocity_command_ = 0.0;
return return_type::ERROR;
}
return return_type::OK;
Expand Down

0 comments on commit 0970d01

Please sign in to comment.