Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -693,7 +693,7 @@ void JointTrajectoryController::query_state_service(
{
const auto logger = get_node()->get_logger();
// Preconditions
if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
if (get_lifecycle_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 @@ -1269,7 +1269,7 @@ rclcpp_action::GoalResponse JointTrajectoryController::goal_received_callback(
RCLCPP_INFO(get_node()->get_logger(), "Received new action goal");

// Precondition: Running controller
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
if (get_lifecycle_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
Original file line number Diff line number Diff line change
Expand Up @@ -421,9 +421,7 @@ class TrajectoryControllerTest : public ::testing::Test
{
if (traj_controller_)
{
if (
traj_controller_->get_lifecycle_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
if (traj_controller_->get_lifecycle_id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
EXPECT_EQ(
traj_controller_->get_node()->deactivate().id(),
Expand Down
Loading