Skip to content

Commit

Permalink
rename get/set_state to get/set_lifecylce_state (ros-controls#1250)
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth authored and RobertWilbrandt committed Sep 19, 2024
1 parent ebd77d5 commit e786d1f
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ controller_interface::return_type DiffDriveController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
auto logger = get_node()->get_logger();
if (get_state().id() == State::PRIMARY_STATE_INACTIVE)
if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE)
{
if (!is_halted)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ controller_interface::return_type JointTrajectoryController::update(
scaling_factor_ = scaling_state_interface_->get().get_value();
}

if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
return controller_interface::return_type::OK;
}
Expand Down Expand Up @@ -631,7 +631,7 @@ void JointTrajectoryController::query_state_service(
{
const auto logger = get_node()->get_logger();
// Preconditions
if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
RCLCPP_ERROR(logger, "Can't sample trajectory. Controller is not active.");
response->success = false;
Expand Down Expand Up @@ -1205,7 +1205,7 @@ rclcpp_action::GoalResponse JointTrajectoryController::goal_received_callback(
RCLCPP_INFO(get_node()->get_logger(), "Received new action goal");

// Precondition: Running controller
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
RCLCPP_ERROR(
get_node()->get_logger(), "Can't accept new action goals. Controller is not running.");
Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ InterfaceConfiguration TricycleController::state_interface_configuration() const
controller_interface::return_type TricycleController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (get_state().id() == State::PRIMARY_STATE_INACTIVE)
if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE)
{
if (!is_halted)
{
Expand Down

0 comments on commit e786d1f

Please sign in to comment.