Skip to content

Commit e786d1f

Browse files
mamueluthRobertWilbrandt
authored andcommitted
rename get/set_state to get/set_lifecylce_state (ros-controls#1250)
1 parent ebd77d5 commit e786d1f

File tree

3 files changed

+5
-5
lines changed

3 files changed

+5
-5
lines changed

diff_drive_controller/src/diff_drive_controller.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ controller_interface::return_type DiffDriveController::update(
101101
const rclcpp::Time & time, const rclcpp::Duration & period)
102102
{
103103
auto logger = get_node()->get_logger();
104-
if (get_state().id() == State::PRIMARY_STATE_INACTIVE)
104+
if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE)
105105
{
106106
if (!is_halted)
107107
{

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,7 @@ controller_interface::return_type JointTrajectoryController::update(
154154
scaling_factor_ = scaling_state_interface_->get().get_value();
155155
}
156156

157-
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
157+
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
158158
{
159159
return controller_interface::return_type::OK;
160160
}
@@ -631,7 +631,7 @@ void JointTrajectoryController::query_state_service(
631631
{
632632
const auto logger = get_node()->get_logger();
633633
// Preconditions
634-
if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
634+
if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
635635
{
636636
RCLCPP_ERROR(logger, "Can't sample trajectory. Controller is not active.");
637637
response->success = false;
@@ -1205,7 +1205,7 @@ rclcpp_action::GoalResponse JointTrajectoryController::goal_received_callback(
12051205
RCLCPP_INFO(get_node()->get_logger(), "Received new action goal");
12061206

12071207
// Precondition: Running controller
1208-
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
1208+
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
12091209
{
12101210
RCLCPP_ERROR(
12111211
get_node()->get_logger(), "Can't accept new action goals. Controller is not running.");

tricycle_controller/src/tricycle_controller.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ InterfaceConfiguration TricycleController::state_interface_configuration() const
8686
controller_interface::return_type TricycleController::update(
8787
const rclcpp::Time & time, const rclcpp::Duration & period)
8888
{
89-
if (get_state().id() == State::PRIMARY_STATE_INACTIVE)
89+
if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE)
9090
{
9191
if (!is_halted)
9292
{

0 commit comments

Comments
 (0)